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

#define MAVLINK_MSG_ID_GPS_RAW_INT 25

lm's avatar
lm committed
5
typedef struct __mavlink_gps_raw_int_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)
 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
 uint16_t hdg; ///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
 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 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_INT_LEN 30
#define MAVLINK_MSG_ID_25_LEN 30



#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
	"GPS_RAW_INT", \
	10, \
	{  { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, usec) }, \
         { "lat", MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
         { "lon", MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
         { "alt", MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \
         { "eph", MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \
         { "epv", MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \
         { "vel", MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \
         { "hdg", MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, hdg) }, \
         { "fix_type", MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
         { "satellites_visible", MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
         } \
}


James Goppert's avatar
James Goppert committed
41 42 43 44 45 46 47 48 49 50
/**
 * @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
 *
 * @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 1E7 degrees
 * @param lon Longitude in 1E7 degrees
LM's avatar
LM committed
51 52 53 54 55 56
 * @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
 * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
 * @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 60
static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       uint64_t 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 hdg, uint8_t satellites_visible)
James Goppert's avatar
James Goppert committed
61 62 63
{
	msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;

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_int32_t_by_index(msg, 8, lat); // Latitude in 1E7 degrees
	put_int32_t_by_index(msg, 12, lon); // Longitude in 1E7 degrees
	put_int32_t_by_index(msg, 16, alt); // Altitude in 1E3 meters (millimeters) above MSL
	put_uint16_t_by_index(msg, 20, eph); // GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
	put_uint16_t_by_index(msg, 22, epv); // GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
	put_uint16_t_by_index(msg, 24, vel); // GPS ground speed (m/s * 100). If unknown, set to: 65535
	put_uint16_t_by_index(msg, 26, hdg); // Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
	put_uint8_t_by_index(msg, 28, 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, 29, satellites_visible); // Number of satellites visible. If unknown, set to 255

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

/**
lm's avatar
lm committed
79
 * @brief Pack a gps_raw_int message on a channel
James Goppert's avatar
James Goppert committed
80 81 82 83 84 85 86 87
 * @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 1E7 degrees
 * @param lon Longitude in 1E7 degrees
LM's avatar
LM committed
88 89 90 91 92 93
 * @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
 * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
 * @param satellites_visible Number of satellites visible. If unknown, set to 255
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_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
						           uint64_t 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 hdg,uint8_t satellites_visible)
{
	msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;

	put_uint64_t_by_index(msg, 0, usec); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	put_int32_t_by_index(msg, 8, lat); // Latitude in 1E7 degrees
	put_int32_t_by_index(msg, 12, lon); // Longitude in 1E7 degrees
	put_int32_t_by_index(msg, 16, alt); // Altitude in 1E3 meters (millimeters) above MSL
	put_uint16_t_by_index(msg, 20, eph); // GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
	put_uint16_t_by_index(msg, 22, epv); // GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
	put_uint16_t_by_index(msg, 24, vel); // GPS ground speed (m/s * 100). If unknown, set to: 65535
	put_uint16_t_by_index(msg, 26, hdg); // Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
	put_uint8_t_by_index(msg, 28, 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, 29, satellites_visible); // Number of satellites visible. If unknown, set to 255

	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 185);
}

James Goppert's avatar
James Goppert committed
116 117 118 119 120 121 122 123 124 125
/**
 * @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)
{
LM's avatar
LM committed
126
	return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->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->hdg, gps_raw_int->satellites_visible);
James Goppert's avatar
James Goppert committed
127 128 129 130 131 132 133 134 135 136
}

/**
 * @brief Send a gps_raw_int 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 1E7 degrees
 * @param lon Longitude in 1E7 degrees
LM's avatar
LM committed
137 138 139 140 141 142
 * @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
 * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
 * @param satellites_visible Number of satellites visible. If unknown, set to 255
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_int_send(mavlink_channel_t chan, uint64_t 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 hdg, uint8_t satellites_visible)
lm's avatar
lm committed
147
{
lm's avatar
lm committed
148
	MAVLINK_ALIGNED_MESSAGE(msg, 30);
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_INT;

	put_uint64_t_by_index(msg, 0, usec); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	put_int32_t_by_index(msg, 8, lat); // Latitude in 1E7 degrees
	put_int32_t_by_index(msg, 12, lon); // Longitude in 1E7 degrees
	put_int32_t_by_index(msg, 16, alt); // Altitude in 1E3 meters (millimeters) above MSL
	put_uint16_t_by_index(msg, 20, eph); // GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
	put_uint16_t_by_index(msg, 22, epv); // GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
	put_uint16_t_by_index(msg, 24, vel); // GPS ground speed (m/s * 100). If unknown, set to: 65535
	put_uint16_t_by_index(msg, 26, hdg); // Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
	put_uint8_t_by_index(msg, 28, 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, 29, satellites_visible); // Number of satellites visible. If unknown, set to 255

	mavlink_finalize_message_chan_send(msg, chan, 30, 185);
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_INT 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_int message
 *
 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 */
static inline uint64_t mavlink_msg_gps_raw_int_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_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
187
	return MAVLINK_MSG_RETURN_uint8_t(msg,  28);
James Goppert's avatar
James Goppert committed
188 189 190 191 192 193 194 195 196
}

/**
 * @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
197
	return MAVLINK_MSG_RETURN_int32_t(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_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
207
	return MAVLINK_MSG_RETURN_int32_t(msg,  12);
James Goppert's avatar
James Goppert committed
208 209 210 211 212
}

/**
 * @brief Get field alt from gps_raw_int message
 *
LM's avatar
LM committed
213
 * @return Altitude in 1E3 meters (millimeters) above MSL
James Goppert's avatar
James Goppert committed
214 215 216
 */
static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg)
{
lm's avatar
lm committed
217
	return MAVLINK_MSG_RETURN_int32_t(msg,  16);
James Goppert's avatar
James Goppert committed
218 219 220 221 222
}

/**
 * @brief Get field eph from gps_raw_int message
 *
LM's avatar
LM committed
223
 * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
224
 */
LM's avatar
LM committed
225
static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
226
{
lm's avatar
lm committed
227
	return MAVLINK_MSG_RETURN_uint16_t(msg,  20);
James Goppert's avatar
James Goppert committed
228 229 230 231 232
}

/**
 * @brief Get field epv from gps_raw_int message
 *
LM's avatar
LM committed
233
 * @return GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
234
 */
LM's avatar
LM committed
235
static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
236
{
lm's avatar
lm committed
237
	return MAVLINK_MSG_RETURN_uint16_t(msg,  22);
James Goppert's avatar
James Goppert committed
238 239 240
}

/**
LM's avatar
LM committed
241
 * @brief Get field vel from gps_raw_int message
James Goppert's avatar
James Goppert committed
242
 *
LM's avatar
LM committed
243
 * @return GPS ground speed (m/s * 100). If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
244
 */
LM's avatar
LM committed
245
static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
246
{
lm's avatar
lm committed
247
	return MAVLINK_MSG_RETURN_uint16_t(msg,  24);
James Goppert's avatar
James Goppert committed
248 249 250 251 252
}

/**
 * @brief Get field hdg from gps_raw_int message
 *
LM's avatar
LM committed
253
 * @return Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
254
 */
LM's avatar
LM committed
255
static inline uint16_t mavlink_msg_gps_raw_int_get_hdg(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
256
{
lm's avatar
lm committed
257
	return MAVLINK_MSG_RETURN_uint16_t(msg,  26);
LM's avatar
LM committed
258 259 260 261 262 263 264 265 266
}

/**
 * @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
267
	return MAVLINK_MSG_RETURN_uint8_t(msg,  29);
James Goppert's avatar
James Goppert committed
268 269 270 271 272 273 274 275 276 277
}

/**
 * @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
278 279 280 281 282 283 284 285 286 287 288 289 290 291
#if MAVLINK_NEED_BYTE_SWAP
	gps_raw_int->usec = mavlink_msg_gps_raw_int_get_usec(msg);
	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);
	gps_raw_int->hdg = mavlink_msg_gps_raw_int_get_hdg(msg);
	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
	memcpy(gps_raw_int, MAVLINK_PAYLOAD(msg), 30);
#endif
James Goppert's avatar
James Goppert committed
292
}