mavlink_msg_gps_raw.h 11.4 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3 4
// MESSAGE GPS_RAW PACKING

#define MAVLINK_MSG_ID_GPS_RAW 32

lm's avatar
lm committed
5
typedef struct __mavlink_gps_raw_t
James Goppert's avatar
James Goppert committed
6
{
lm's avatar
lm committed
7 8 9 10 11 12 13 14 15 16
 uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 float lat; ///< Latitude in degrees
 float lon; ///< Longitude in degrees
 float alt; ///< Altitude in meters
 float eph; ///< GPS HDOP
 float epv; ///< GPS VDOP
 float v; ///< GPS ground speed
 float hdg; ///< Compass heading in degrees, 0..360 degrees
 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
James Goppert's avatar
James Goppert committed
17 18
} mavlink_gps_raw_t;

lm's avatar
lm committed
19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40
#define MAVLINK_MSG_ID_GPS_RAW_LEN 38
#define MAVLINK_MSG_ID_32_LEN 38



#define MAVLINK_MESSAGE_INFO_GPS_RAW { \
	"GPS_RAW", \
	10, \
	{  { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_t, usec) }, \
         { "lat", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gps_raw_t, lat) }, \
         { "lon", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gps_raw_t, lon) }, \
         { "alt", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gps_raw_t, alt) }, \
         { "eph", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_raw_t, eph) }, \
         { "epv", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gps_raw_t, epv) }, \
         { "v", MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gps_raw_t, v) }, \
         { "hdg", MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_raw_t, hdg) }, \
         { "fix_type", MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_gps_raw_t, fix_type) }, \
         { "satellites_visible", MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_gps_raw_t, satellites_visible) }, \
         } \
}


James Goppert's avatar
James Goppert committed
41 42 43 44 45 46 47 48 49 50 51 52 53 54 55
/**
 * @brief Pack a gps_raw 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 * @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 degrees
 * @param lon Longitude in degrees
 * @param alt Altitude in meters
 * @param eph GPS HDOP
 * @param epv GPS VDOP
 * @param v GPS ground speed
 * @param hdg Compass heading in degrees, 0..360 degrees
LM's avatar
LM committed
56
 * @param satellites_visible Number of satellites visible
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 60
static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg, uint8_t satellites_visible)
James Goppert's avatar
James Goppert committed
61 62 63
{
	msg->msgid = MAVLINK_MSG_ID_GPS_RAW;

lm's avatar
lm committed
64 65 66 67 68 69 70 71 72 73 74 75
	put_uint64_t_by_index(msg, 0, usec); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	put_float_by_index(msg, 8, lat); // Latitude in degrees
	put_float_by_index(msg, 12, lon); // Longitude in degrees
	put_float_by_index(msg, 16, alt); // Altitude in meters
	put_float_by_index(msg, 20, eph); // GPS HDOP
	put_float_by_index(msg, 24, epv); // GPS VDOP
	put_float_by_index(msg, 28, v); // GPS ground speed
	put_float_by_index(msg, 32, hdg); // Compass heading in degrees, 0..360 degrees
	put_uint8_t_by_index(msg, 36, 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.
	put_uint8_t_by_index(msg, 37, satellites_visible); // Number of satellites visible

	return mavlink_finalize_message(msg, system_id, component_id, 38, 198);
James Goppert's avatar
James Goppert committed
76 77 78
}

/**
lm's avatar
lm committed
79
 * @brief Pack a gps_raw message on a channel
James Goppert's avatar
James Goppert committed
80 81 82 83 84 85 86 87 88 89 90 91 92
 * @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
 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 * @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 degrees
 * @param lon Longitude in degrees
 * @param alt Altitude in meters
 * @param eph GPS HDOP
 * @param epv GPS VDOP
 * @param v GPS ground speed
 * @param hdg Compass heading in degrees, 0..360 degrees
LM's avatar
LM committed
93
 * @param satellites_visible Number of satellites visible
James Goppert's avatar
James Goppert committed
94 95
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115
static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
						           uint64_t usec,uint8_t fix_type,float lat,float lon,float alt,float eph,float epv,float v,float hdg,uint8_t satellites_visible)
{
	msg->msgid = MAVLINK_MSG_ID_GPS_RAW;

	put_uint64_t_by_index(msg, 0, usec); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	put_float_by_index(msg, 8, lat); // Latitude in degrees
	put_float_by_index(msg, 12, lon); // Longitude in degrees
	put_float_by_index(msg, 16, alt); // Altitude in meters
	put_float_by_index(msg, 20, eph); // GPS HDOP
	put_float_by_index(msg, 24, epv); // GPS VDOP
	put_float_by_index(msg, 28, v); // GPS ground speed
	put_float_by_index(msg, 32, hdg); // Compass heading in degrees, 0..360 degrees
	put_uint8_t_by_index(msg, 36, 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.
	put_uint8_t_by_index(msg, 37, satellites_visible); // Number of satellites visible

	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 38, 198);
}

James Goppert's avatar
James Goppert committed
116 117 118 119 120 121 122 123 124 125
/**
 * @brief Encode a gps_raw 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 C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_t* gps_raw)
{
LM's avatar
LM committed
126
	return mavlink_msg_gps_raw_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->alt, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg, gps_raw->satellites_visible);
James Goppert's avatar
James Goppert committed
127 128 129 130 131 132 133 134 135 136 137 138 139 140 141
}

/**
 * @brief Send a gps_raw message
 * @param chan MAVLink channel to send the message
 *
 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 * @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 degrees
 * @param lon Longitude in degrees
 * @param alt Altitude in meters
 * @param eph GPS HDOP
 * @param epv GPS VDOP
 * @param v GPS ground speed
 * @param hdg Compass heading in degrees, 0..360 degrees
LM's avatar
LM committed
142
 * @param satellites_visible Number of satellites visible
James Goppert's avatar
James Goppert committed
143
 */
lm's avatar
lm committed
144 145
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

LM's avatar
LM committed
146
static inline void mavlink_msg_gps_raw_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg, uint8_t satellites_visible)
lm's avatar
lm committed
147
{
lm's avatar
lm committed
148
	MAVLINK_ALIGNED_MESSAGE(msg, 38);
LM's avatar
LM committed
149 150 151 152 153 154 155 156 157 158 159 160 161 162
	msg->msgid = MAVLINK_MSG_ID_GPS_RAW;

	put_uint64_t_by_index(msg, 0, usec); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	put_float_by_index(msg, 8, lat); // Latitude in degrees
	put_float_by_index(msg, 12, lon); // Longitude in degrees
	put_float_by_index(msg, 16, alt); // Altitude in meters
	put_float_by_index(msg, 20, eph); // GPS HDOP
	put_float_by_index(msg, 24, epv); // GPS VDOP
	put_float_by_index(msg, 28, v); // GPS ground speed
	put_float_by_index(msg, 32, hdg); // Compass heading in degrees, 0..360 degrees
	put_uint8_t_by_index(msg, 36, 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.
	put_uint8_t_by_index(msg, 37, satellites_visible); // Number of satellites visible

	mavlink_finalize_message_chan_send(msg, chan, 38, 198);
James Goppert's avatar
James Goppert committed
163 164 165
}

#endif
lm's avatar
lm committed
166

James Goppert's avatar
James Goppert committed
167 168
// MESSAGE GPS_RAW UNPACKING

lm's avatar
lm committed
169

James Goppert's avatar
James Goppert committed
170 171 172 173 174 175 176
/**
 * @brief Get field usec from gps_raw message
 *
 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 */
static inline uint64_t mavlink_msg_gps_raw_get_usec(const mavlink_message_t* msg)
{
lm's avatar
lm committed
177
	return MAVLINK_MSG_RETURN_uint64_t(msg,  0);
James Goppert's avatar
James Goppert committed
178 179 180 181 182 183 184 185 186
}

/**
 * @brief Get field fix_type from gps_raw 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_get_fix_type(const mavlink_message_t* msg)
{
lm's avatar
lm committed
187
	return MAVLINK_MSG_RETURN_uint8_t(msg,  36);
James Goppert's avatar
James Goppert committed
188 189 190 191 192 193 194 195 196
}

/**
 * @brief Get field lat from gps_raw message
 *
 * @return Latitude in degrees
 */
static inline float mavlink_msg_gps_raw_get_lat(const mavlink_message_t* msg)
{
lm's avatar
lm committed
197
	return MAVLINK_MSG_RETURN_float(msg,  8);
James Goppert's avatar
James Goppert committed
198 199 200 201 202 203 204 205 206
}

/**
 * @brief Get field lon from gps_raw message
 *
 * @return Longitude in degrees
 */
static inline float mavlink_msg_gps_raw_get_lon(const mavlink_message_t* msg)
{
lm's avatar
lm committed
207
	return MAVLINK_MSG_RETURN_float(msg,  12);
James Goppert's avatar
James Goppert committed
208 209 210 211 212 213 214 215 216
}

/**
 * @brief Get field alt from gps_raw message
 *
 * @return Altitude in meters
 */
static inline float mavlink_msg_gps_raw_get_alt(const mavlink_message_t* msg)
{
lm's avatar
lm committed
217
	return MAVLINK_MSG_RETURN_float(msg,  16);
James Goppert's avatar
James Goppert committed
218 219 220 221 222 223 224 225 226
}

/**
 * @brief Get field eph from gps_raw message
 *
 * @return GPS HDOP
 */
static inline float mavlink_msg_gps_raw_get_eph(const mavlink_message_t* msg)
{
lm's avatar
lm committed
227
	return MAVLINK_MSG_RETURN_float(msg,  20);
James Goppert's avatar
James Goppert committed
228 229 230 231 232 233 234 235 236
}

/**
 * @brief Get field epv from gps_raw message
 *
 * @return GPS VDOP
 */
static inline float mavlink_msg_gps_raw_get_epv(const mavlink_message_t* msg)
{
lm's avatar
lm committed
237
	return MAVLINK_MSG_RETURN_float(msg,  24);
James Goppert's avatar
James Goppert committed
238 239 240 241 242 243 244 245 246
}

/**
 * @brief Get field v from gps_raw message
 *
 * @return GPS ground speed
 */
static inline float mavlink_msg_gps_raw_get_v(const mavlink_message_t* msg)
{
lm's avatar
lm committed
247
	return MAVLINK_MSG_RETURN_float(msg,  28);
James Goppert's avatar
James Goppert committed
248 249 250 251 252 253 254 255 256
}

/**
 * @brief Get field hdg from gps_raw message
 *
 * @return Compass heading in degrees, 0..360 degrees
 */
static inline float mavlink_msg_gps_raw_get_hdg(const mavlink_message_t* msg)
{
lm's avatar
lm committed
257
	return MAVLINK_MSG_RETURN_float(msg,  32);
James Goppert's avatar
James Goppert committed
258 259
}

LM's avatar
LM committed
260 261 262 263 264 265 266
/**
 * @brief Get field satellites_visible from gps_raw message
 *
 * @return Number of satellites visible
 */
static inline uint8_t mavlink_msg_gps_raw_get_satellites_visible(const mavlink_message_t* msg)
{
lm's avatar
lm committed
267
	return MAVLINK_MSG_RETURN_uint8_t(msg,  37);
LM's avatar
LM committed
268 269
}

James Goppert's avatar
James Goppert committed
270 271 272 273 274 275 276 277
/**
 * @brief Decode a gps_raw message into a struct
 *
 * @param msg The message to decode
 * @param gps_raw C-struct to decode the message contents into
 */
static inline void mavlink_msg_gps_raw_decode(const mavlink_message_t* msg, mavlink_gps_raw_t* gps_raw)
{
lm's avatar
lm committed
278 279 280 281 282 283 284 285 286 287 288 289 290 291
#if MAVLINK_NEED_BYTE_SWAP
	gps_raw->usec = mavlink_msg_gps_raw_get_usec(msg);
	gps_raw->lat = mavlink_msg_gps_raw_get_lat(msg);
	gps_raw->lon = mavlink_msg_gps_raw_get_lon(msg);
	gps_raw->alt = mavlink_msg_gps_raw_get_alt(msg);
	gps_raw->eph = mavlink_msg_gps_raw_get_eph(msg);
	gps_raw->epv = mavlink_msg_gps_raw_get_epv(msg);
	gps_raw->v = mavlink_msg_gps_raw_get_v(msg);
	gps_raw->hdg = mavlink_msg_gps_raw_get_hdg(msg);
	gps_raw->fix_type = mavlink_msg_gps_raw_get_fix_type(msg);
	gps_raw->satellites_visible = mavlink_msg_gps_raw_get_satellites_visible(msg);
#else
	memcpy(gps_raw, MAVLINK_PAYLOAD(msg), 38);
#endif
James Goppert's avatar
James Goppert committed
292
}