mavlink_msg_gps_raw_int.h 13.5 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2
// MESSAGE GPS_RAW_INT PACKING

lm's avatar
lm committed
3
#define MAVLINK_MSG_ID_GPS_RAW_INT 24
James Goppert's avatar
James Goppert committed
4

lm's avatar
lm committed
5
typedef struct __mavlink_gps_raw_int_t
James Goppert's avatar
James Goppert committed
6
{
7
 uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
lm's avatar
lm committed
8 9 10 11 12 13
 int32_t lat; ///< Latitude in 1E7 degrees
 int32_t lon; ///< Longitude in 1E7 degrees
 int32_t alt; ///< Altitude in 1E3 meters (millimeters) above MSL
 uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
 uint16_t epv; ///< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
 uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: 65535
14
 uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
lm's avatar
lm committed
15 16
 uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
 uint8_t satellites_visible; ///< Number of satellites visible. If unknown, set to 255
James Goppert's avatar
James Goppert committed
17 18
} mavlink_gps_raw_int_t;

lm's avatar
lm committed
19
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30
lm's avatar
lm committed
20
#define MAVLINK_MSG_ID_24_LEN 30
lm's avatar
lm committed
21 22 23 24 25 26



#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
	"GPS_RAW_INT", \
	10, \
lm's avatar
lm committed
27 28 29 30 31 32 33 34 35 36
	{  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
         { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
         { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
         { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \
         { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \
         { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \
         { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \
         { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \
         { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
         { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
lm's avatar
lm committed
37 38 39 40
         } \
}


James Goppert's avatar
James Goppert committed
41 42 43 44 45 46
/**
 * @brief Pack a gps_raw_int message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 *
47
 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
James Goppert's avatar
James Goppert committed
48 49 50
 * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
 * @param lat Latitude in 1E7 degrees
 * @param lon Longitude in 1E7 degrees
LM's avatar
LM committed
51 52 53 54
 * @param alt Altitude in 1E3 meters (millimeters) above MSL
 * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
 * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
 * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
55
 * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
LM's avatar
LM committed
56
 * @param satellites_visible Number of satellites visible. If unknown, set to 255
James Goppert's avatar
James Goppert committed
57 58
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
59
static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
60
						       uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible)
James Goppert's avatar
James Goppert committed
61
{
LM's avatar
LM committed
62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[30];
	_mav_put_uint64_t(buf, 0, time_usec);
	_mav_put_int32_t(buf, 8, lat);
	_mav_put_int32_t(buf, 12, lon);
	_mav_put_int32_t(buf, 16, alt);
	_mav_put_uint16_t(buf, 20, eph);
	_mav_put_uint16_t(buf, 22, epv);
	_mav_put_uint16_t(buf, 24, vel);
	_mav_put_uint16_t(buf, 26, cog);
	_mav_put_uint8_t(buf, 28, fix_type);
	_mav_put_uint8_t(buf, 29, satellites_visible);

        memcpy(_MAV_PAYLOAD(msg), buf, 30);
#else
	mavlink_gps_raw_int_t packet;
	packet.time_usec = time_usec;
	packet.lat = lat;
	packet.lon = lon;
	packet.alt = alt;
	packet.eph = eph;
	packet.epv = epv;
	packet.vel = vel;
	packet.cog = cog;
	packet.fix_type = fix_type;
	packet.satellites_visible = satellites_visible;

        memcpy(_MAV_PAYLOAD(msg), &packet, 30);
#endif
lm's avatar
lm committed
91

LM's avatar
LM committed
92
	msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
93
	return mavlink_finalize_message(msg, system_id, component_id, 30, 24);
James Goppert's avatar
James Goppert committed
94 95 96
}

/**
lm's avatar
lm committed
97
 * @brief Pack a gps_raw_int message on a channel
James Goppert's avatar
James Goppert committed
98 99 100 101
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
102
 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
James Goppert's avatar
James Goppert committed
103 104 105
 * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
 * @param lat Latitude in 1E7 degrees
 * @param lon Longitude in 1E7 degrees
LM's avatar
LM committed
106 107 108 109
 * @param alt Altitude in 1E3 meters (millimeters) above MSL
 * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
 * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
 * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
110
 * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
LM's avatar
LM committed
111
 * @param satellites_visible Number of satellites visible. If unknown, set to 255
James Goppert's avatar
James Goppert committed
112 113
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
114 115
static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
116
						           uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible)
lm's avatar
lm committed
117
{
LM's avatar
LM committed
118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[30];
	_mav_put_uint64_t(buf, 0, time_usec);
	_mav_put_int32_t(buf, 8, lat);
	_mav_put_int32_t(buf, 12, lon);
	_mav_put_int32_t(buf, 16, alt);
	_mav_put_uint16_t(buf, 20, eph);
	_mav_put_uint16_t(buf, 22, epv);
	_mav_put_uint16_t(buf, 24, vel);
	_mav_put_uint16_t(buf, 26, cog);
	_mav_put_uint8_t(buf, 28, fix_type);
	_mav_put_uint8_t(buf, 29, satellites_visible);

        memcpy(_MAV_PAYLOAD(msg), buf, 30);
#else
	mavlink_gps_raw_int_t packet;
	packet.time_usec = time_usec;
	packet.lat = lat;
	packet.lon = lon;
	packet.alt = alt;
	packet.eph = eph;
	packet.epv = epv;
	packet.vel = vel;
	packet.cog = cog;
	packet.fix_type = fix_type;
	packet.satellites_visible = satellites_visible;

        memcpy(_MAV_PAYLOAD(msg), &packet, 30);
#endif
lm's avatar
lm committed
147

LM's avatar
LM committed
148
	msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
149
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 24);
lm's avatar
lm committed
150 151
}

James Goppert's avatar
James Goppert committed
152 153 154 155 156 157 158 159 160 161
/**
 * @brief Encode a gps_raw_int struct into a message
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 * @param gps_raw_int C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int)
{
162
	return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible);
James Goppert's avatar
James Goppert committed
163 164 165 166 167 168
}

/**
 * @brief Send a gps_raw_int message
 * @param chan MAVLink channel to send the message
 *
169
 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
James Goppert's avatar
James Goppert committed
170 171 172
 * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
 * @param lat Latitude in 1E7 degrees
 * @param lon Longitude in 1E7 degrees
LM's avatar
LM committed
173 174 175 176
 * @param alt Altitude in 1E3 meters (millimeters) above MSL
 * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
 * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
 * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
177
 * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
LM's avatar
LM committed
178
 * @param satellites_visible Number of satellites visible. If unknown, set to 255
James Goppert's avatar
James Goppert committed
179
 */
lm's avatar
lm committed
180 181
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

182
static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible)
lm's avatar
lm committed
183
{
LM's avatar
LM committed
184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[30];
	_mav_put_uint64_t(buf, 0, time_usec);
	_mav_put_int32_t(buf, 8, lat);
	_mav_put_int32_t(buf, 12, lon);
	_mav_put_int32_t(buf, 16, alt);
	_mav_put_uint16_t(buf, 20, eph);
	_mav_put_uint16_t(buf, 22, epv);
	_mav_put_uint16_t(buf, 24, vel);
	_mav_put_uint16_t(buf, 26, cog);
	_mav_put_uint8_t(buf, 28, fix_type);
	_mav_put_uint8_t(buf, 29, satellites_visible);

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, 30, 24);
#else
	mavlink_gps_raw_int_t packet;
	packet.time_usec = time_usec;
	packet.lat = lat;
	packet.lon = lon;
	packet.alt = alt;
	packet.eph = eph;
	packet.epv = epv;
	packet.vel = vel;
	packet.cog = cog;
	packet.fix_type = fix_type;
	packet.satellites_visible = satellites_visible;

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, 30, 24);
#endif
James Goppert's avatar
James Goppert committed
213 214 215
}

#endif
lm's avatar
lm committed
216

James Goppert's avatar
James Goppert committed
217 218
// MESSAGE GPS_RAW_INT UNPACKING

lm's avatar
lm committed
219

James Goppert's avatar
James Goppert committed
220
/**
221
 * @brief Get field time_usec from gps_raw_int message
James Goppert's avatar
James Goppert committed
222 223 224
 *
 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 */
225
static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
226
{
LM's avatar
LM committed
227
	return _MAV_RETURN_uint64_t(msg,  0);
James Goppert's avatar
James Goppert committed
228 229 230 231 232 233 234 235 236
}

/**
 * @brief Get field fix_type from gps_raw_int message
 *
 * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
 */
static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg)
{
LM's avatar
LM committed
237
	return _MAV_RETURN_uint8_t(msg,  28);
James Goppert's avatar
James Goppert committed
238 239 240 241 242 243 244 245 246
}

/**
 * @brief Get field lat from gps_raw_int message
 *
 * @return Latitude in 1E7 degrees
 */
static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg)
{
LM's avatar
LM committed
247
	return _MAV_RETURN_int32_t(msg,  8);
James Goppert's avatar
James Goppert committed
248 249 250 251 252 253 254 255 256
}

/**
 * @brief Get field lon from gps_raw_int message
 *
 * @return Longitude in 1E7 degrees
 */
static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg)
{
LM's avatar
LM committed
257
	return _MAV_RETURN_int32_t(msg,  12);
James Goppert's avatar
James Goppert committed
258 259 260 261 262
}

/**
 * @brief Get field alt from gps_raw_int message
 *
LM's avatar
LM committed
263
 * @return Altitude in 1E3 meters (millimeters) above MSL
James Goppert's avatar
James Goppert committed
264 265 266
 */
static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg)
{
LM's avatar
LM committed
267
	return _MAV_RETURN_int32_t(msg,  16);
James Goppert's avatar
James Goppert committed
268 269 270 271 272
}

/**
 * @brief Get field eph from gps_raw_int message
 *
LM's avatar
LM committed
273
 * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
274
 */
LM's avatar
LM committed
275
static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
276
{
LM's avatar
LM committed
277
	return _MAV_RETURN_uint16_t(msg,  20);
James Goppert's avatar
James Goppert committed
278 279 280 281 282
}

/**
 * @brief Get field epv from gps_raw_int message
 *
LM's avatar
LM committed
283
 * @return GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
284
 */
LM's avatar
LM committed
285
static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
286
{
LM's avatar
LM committed
287
	return _MAV_RETURN_uint16_t(msg,  22);
James Goppert's avatar
James Goppert committed
288 289 290
}

/**
LM's avatar
LM committed
291
 * @brief Get field vel from gps_raw_int message
James Goppert's avatar
James Goppert committed
292
 *
LM's avatar
LM committed
293
 * @return GPS ground speed (m/s * 100). If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
294
 */
LM's avatar
LM committed
295
static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
296
{
LM's avatar
LM committed
297
	return _MAV_RETURN_uint16_t(msg,  24);
James Goppert's avatar
James Goppert committed
298 299 300
}

/**
301
 * @brief Get field cog from gps_raw_int message
James Goppert's avatar
James Goppert committed
302
 *
303
 * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
304
 */
305
static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
306
{
LM's avatar
LM committed
307
	return _MAV_RETURN_uint16_t(msg,  26);
LM's avatar
LM committed
308 309 310 311 312 313 314 315 316
}

/**
 * @brief Get field satellites_visible from gps_raw_int message
 *
 * @return Number of satellites visible. If unknown, set to 255
 */
static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg)
{
LM's avatar
LM committed
317
	return _MAV_RETURN_uint8_t(msg,  29);
James Goppert's avatar
James Goppert committed
318 319 320 321 322 323 324 325 326 327
}

/**
 * @brief Decode a gps_raw_int message into a struct
 *
 * @param msg The message to decode
 * @param gps_raw_int C-struct to decode the message contents into
 */
static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int)
{
lm's avatar
lm committed
328
#if MAVLINK_NEED_BYTE_SWAP
329
	gps_raw_int->time_usec = mavlink_msg_gps_raw_int_get_time_usec(msg);
lm's avatar
lm committed
330 331 332 333 334 335
	gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg);
	gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg);
	gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg);
	gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg);
	gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg);
	gps_raw_int->vel = mavlink_msg_gps_raw_int_get_vel(msg);
336
	gps_raw_int->cog = mavlink_msg_gps_raw_int_get_cog(msg);
lm's avatar
lm committed
337 338 339
	gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg);
	gps_raw_int->satellites_visible = mavlink_msg_gps_raw_int_get_satellites_visible(msg);
#else
LM's avatar
LM committed
340
	memcpy(gps_raw_int, _MAV_PAYLOAD(msg), 30);
lm's avatar
lm committed
341
#endif
James Goppert's avatar
James Goppert committed
342
}