3 #define MAVLINK_MSG_ID_GPS2_RAW 124
21 #define MAVLINK_MSG_ID_GPS2_RAW_LEN 35
22 #define MAVLINK_MSG_ID_124_LEN 35
24 #define MAVLINK_MSG_ID_GPS2_RAW_CRC 87
25 #define MAVLINK_MSG_ID_124_CRC 87
29 #define MAVLINK_MESSAGE_INFO_GPS2_RAW { \
32 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \
33 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \
34 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \
35 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \
36 { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \
37 { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \
38 { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \
39 { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \
40 { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \
41 { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \
42 { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \
43 { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \
68 static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
69 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, uint8_t dgps_numch, uint32_t dgps_age)
71 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
72 char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
73 _mav_put_uint64_t(buf, 0, time_usec);
74 _mav_put_int32_t(buf, 8, lat);
75 _mav_put_int32_t(buf, 12, lon);
76 _mav_put_int32_t(buf, 16, alt);
77 _mav_put_uint32_t(buf, 20, dgps_age);
78 _mav_put_uint16_t(buf, 24, eph);
79 _mav_put_uint16_t(buf, 26, epv);
80 _mav_put_uint16_t(buf, 28, vel);
81 _mav_put_uint16_t(buf, 30, cog);
82 _mav_put_uint8_t(buf, 32, fix_type);
83 _mav_put_uint8_t(buf, 33, satellites_visible);
84 _mav_put_uint8_t(buf, 34, dgps_numch);
86 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
102 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
105 msg->msgid = MAVLINK_MSG_ID_GPS2_RAW;
106 #if MAVLINK_CRC_EXTRA
107 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
109 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN);
133 static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
134 mavlink_message_t* msg,
135 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,uint8_t dgps_numch,uint32_t dgps_age)
137 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
138 char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
139 _mav_put_uint64_t(buf, 0, time_usec);
140 _mav_put_int32_t(buf, 8, lat);
141 _mav_put_int32_t(buf, 12, lon);
142 _mav_put_int32_t(buf, 16, alt);
143 _mav_put_uint32_t(buf, 20, dgps_age);
144 _mav_put_uint16_t(buf, 24, eph);
145 _mav_put_uint16_t(buf, 26, epv);
146 _mav_put_uint16_t(buf, 28, vel);
147 _mav_put_uint16_t(buf, 30, cog);
148 _mav_put_uint8_t(buf, 32, fix_type);
149 _mav_put_uint8_t(buf, 33, satellites_visible);
150 _mav_put_uint8_t(buf, 34, dgps_numch);
152 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
168 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
171 msg->msgid = MAVLINK_MSG_ID_GPS2_RAW;
172 #if MAVLINK_CRC_EXTRA
173 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
175 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN);
187 static inline uint16_t mavlink_msg_gps2_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_gps2_raw_t* gps2_raw)
189 return mavlink_msg_gps2_raw_pack(system_id, component_id, msg, gps2_raw->
time_usec, gps2_raw->
fix_type, gps2_raw->
lat, gps2_raw->
lon, gps2_raw->
alt, gps2_raw->
eph, gps2_raw->
epv, gps2_raw->
vel, gps2_raw->
cog, gps2_raw->
satellites_visible, gps2_raw->
dgps_numch, gps2_raw->
dgps_age);
201 static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_gps2_raw_t* gps2_raw)
203 return mavlink_msg_gps2_raw_pack_chan(system_id, component_id, chan, msg, gps2_raw->
time_usec, gps2_raw->
fix_type, gps2_raw->
lat, gps2_raw->
lon, gps2_raw->
alt, gps2_raw->
eph, gps2_raw->
epv, gps2_raw->
vel, gps2_raw->
cog, gps2_raw->
satellites_visible, gps2_raw->
dgps_numch, gps2_raw->
dgps_age);
223 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
225 static inline void mavlink_msg_gps2_raw_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, uint8_t dgps_numch, uint32_t dgps_age)
227 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
228 char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
229 _mav_put_uint64_t(buf, 0, time_usec);
230 _mav_put_int32_t(buf, 8, lat);
231 _mav_put_int32_t(buf, 12, lon);
232 _mav_put_int32_t(buf, 16, alt);
233 _mav_put_uint32_t(buf, 20, dgps_age);
234 _mav_put_uint16_t(buf, 24, eph);
235 _mav_put_uint16_t(buf, 26, epv);
236 _mav_put_uint16_t(buf, 28, vel);
237 _mav_put_uint16_t(buf, 30, cog);
238 _mav_put_uint8_t(buf, 32, fix_type);
239 _mav_put_uint8_t(buf, 33, satellites_visible);
240 _mav_put_uint8_t(buf, 34, dgps_numch);
242 #if MAVLINK_CRC_EXTRA
243 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
245 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
262 #if MAVLINK_CRC_EXTRA
263 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (
const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
265 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (
const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
270 #if MAVLINK_MSG_ID_GPS2_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
278 static inline void mavlink_msg_gps2_raw_send_buf(mavlink_message_t *msgbuf, 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, uint8_t dgps_numch, uint32_t dgps_age)
280 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
281 char *buf = (
char *)msgbuf;
282 _mav_put_uint64_t(buf, 0, time_usec);
283 _mav_put_int32_t(buf, 8, lat);
284 _mav_put_int32_t(buf, 12, lon);
285 _mav_put_int32_t(buf, 16, alt);
286 _mav_put_uint32_t(buf, 20, dgps_age);
287 _mav_put_uint16_t(buf, 24, eph);
288 _mav_put_uint16_t(buf, 26, epv);
289 _mav_put_uint16_t(buf, 28, vel);
290 _mav_put_uint16_t(buf, 30, cog);
291 _mav_put_uint8_t(buf, 32, fix_type);
292 _mav_put_uint8_t(buf, 33, satellites_visible);
293 _mav_put_uint8_t(buf, 34, dgps_numch);
295 #if MAVLINK_CRC_EXTRA
296 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
298 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
315 #if MAVLINK_CRC_EXTRA
316 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (
const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
318 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (
const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
334 static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(
const mavlink_message_t* msg)
336 return _MAV_RETURN_uint64_t(msg, 0);
344 static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(
const mavlink_message_t* msg)
346 return _MAV_RETURN_uint8_t(msg, 32);
354 static inline int32_t mavlink_msg_gps2_raw_get_lat(
const mavlink_message_t* msg)
356 return _MAV_RETURN_int32_t(msg, 8);
364 static inline int32_t mavlink_msg_gps2_raw_get_lon(
const mavlink_message_t* msg)
366 return _MAV_RETURN_int32_t(msg, 12);
374 static inline int32_t mavlink_msg_gps2_raw_get_alt(
const mavlink_message_t* msg)
376 return _MAV_RETURN_int32_t(msg, 16);
384 static inline uint16_t mavlink_msg_gps2_raw_get_eph(
const mavlink_message_t* msg)
386 return _MAV_RETURN_uint16_t(msg, 24);
394 static inline uint16_t mavlink_msg_gps2_raw_get_epv(
const mavlink_message_t* msg)
396 return _MAV_RETURN_uint16_t(msg, 26);
404 static inline uint16_t mavlink_msg_gps2_raw_get_vel(
const mavlink_message_t* msg)
406 return _MAV_RETURN_uint16_t(msg, 28);
414 static inline uint16_t mavlink_msg_gps2_raw_get_cog(
const mavlink_message_t* msg)
416 return _MAV_RETURN_uint16_t(msg, 30);
424 static inline uint8_t mavlink_msg_gps2_raw_get_satellites_visible(
const mavlink_message_t* msg)
426 return _MAV_RETURN_uint8_t(msg, 33);
434 static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(
const mavlink_message_t* msg)
436 return _MAV_RETURN_uint8_t(msg, 34);
444 static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(
const mavlink_message_t* msg)
446 return _MAV_RETURN_uint32_t(msg, 20);
455 static inline void mavlink_msg_gps2_raw_decode(
const mavlink_message_t* msg,
mavlink_gps2_raw_t* gps2_raw)
457 #if MAVLINK_NEED_BYTE_SWAP
458 gps2_raw->
time_usec = mavlink_msg_gps2_raw_get_time_usec(msg);
459 gps2_raw->
lat = mavlink_msg_gps2_raw_get_lat(msg);
460 gps2_raw->
lon = mavlink_msg_gps2_raw_get_lon(msg);
461 gps2_raw->
alt = mavlink_msg_gps2_raw_get_alt(msg);
462 gps2_raw->
dgps_age = mavlink_msg_gps2_raw_get_dgps_age(msg);
463 gps2_raw->
eph = mavlink_msg_gps2_raw_get_eph(msg);
464 gps2_raw->
epv = mavlink_msg_gps2_raw_get_epv(msg);
465 gps2_raw->
vel = mavlink_msg_gps2_raw_get_vel(msg);
466 gps2_raw->
cog = mavlink_msg_gps2_raw_get_cog(msg);
467 gps2_raw->
fix_type = mavlink_msg_gps2_raw_get_fix_type(msg);
469 gps2_raw->
dgps_numch = mavlink_msg_gps2_raw_get_dgps_numch(msg);
471 memcpy(gps2_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS2_RAW_LEN);
uint16_t vel
GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX.
Definition: mavlink_msg_gps2_raw.h:14
int32_t lat
Latitude (WGS84), in degrees * 1E7.
Definition: mavlink_msg_gps2_raw.h:8
uint16_t cog
Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX.
Definition: mavlink_msg_gps2_raw.h:15
uint64_t time_usec
Timestamp (microseconds since UNIX epoch or microseconds since system boot)
Definition: mavlink_msg_gps2_raw.h:7
int32_t lon
Longitude (WGS84), in degrees * 1E7.
Definition: mavlink_msg_gps2_raw.h:9
uint8_t satellites_visible
Number of satellites visible. If unknown, set to 255.
Definition: mavlink_msg_gps2_raw.h:17
uint16_t epv
GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX.
Definition: mavlink_msg_gps2_raw.h:13
uint16_t eph
GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX.
Definition: mavlink_msg_gps2_raw.h:12
uint8_t fix_type
0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value ...
Definition: mavlink_msg_gps2_raw.h:16
Definition: mavlink_msg_gps2_raw.h:5
int32_t alt
Altitude (WGS84), in meters * 1000 (positive for up)
Definition: mavlink_msg_gps2_raw.h:10
uint8_t dgps_numch
Number of DGPS satellites.
Definition: mavlink_msg_gps2_raw.h:18
uint32_t dgps_age
Age of DGPS info.
Definition: mavlink_msg_gps2_raw.h:11