mavlink_msg_gps2_raw.h
Go to the documentation of this file.
1 // MESSAGE GPS2_RAW PACKING
2 
3 #define MAVLINK_MSG_ID_GPS2_RAW 124
4 
5 typedef struct __mavlink_gps2_raw_t
6 {
7  uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
8  int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/
9  int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/
10  int32_t alt; /*< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)*/
11  uint32_t dgps_age; /*< Age of DGPS info*/
12  uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/
13  uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/
14  uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX*/
15  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*/
16  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 of this field unless it is at least two, so always correctly fill in the fix.*/
17  uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/
18  uint8_t dgps_numch; /*< Number of DGPS satellites*/
20 
21 #define MAVLINK_MSG_ID_GPS2_RAW_LEN 35
22 #define MAVLINK_MSG_ID_124_LEN 35
23 
24 #define MAVLINK_MSG_ID_GPS2_RAW_CRC 87
25 #define MAVLINK_MSG_ID_124_CRC 87
26 
27 
28 
29 #define MAVLINK_MESSAGE_INFO_GPS2_RAW { \
30  "GPS2_RAW", \
31  12, \
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) }, \
44  } \
45 }
46 
47 
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)
70 {
71 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
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);
85 
87 #else
88  mavlink_gps2_raw_t packet;
89  packet.time_usec = time_usec;
90  packet.lat = lat;
91  packet.lon = lon;
92  packet.alt = alt;
93  packet.dgps_age = dgps_age;
94  packet.eph = eph;
95  packet.epv = epv;
96  packet.vel = vel;
97  packet.cog = cog;
98  packet.fix_type = fix_type;
100  packet.dgps_numch = dgps_numch;
101 
103 #endif
104 
105  msg->msgid = MAVLINK_MSG_ID_GPS2_RAW;
106 #if MAVLINK_CRC_EXTRA
108 #else
109  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN);
110 #endif
111 }
112 
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)
136 {
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);
151 
153 #else
154  mavlink_gps2_raw_t packet;
155  packet.time_usec = time_usec;
156  packet.lat = lat;
157  packet.lon = lon;
158  packet.alt = alt;
159  packet.dgps_age = dgps_age;
160  packet.eph = eph;
161  packet.epv = epv;
162  packet.vel = vel;
163  packet.cog = cog;
164  packet.fix_type = fix_type;
166  packet.dgps_numch = dgps_numch;
167 
169 #endif
170 
171  msg->msgid = MAVLINK_MSG_ID_GPS2_RAW;
172 #if MAVLINK_CRC_EXTRA
174 #else
175  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN);
176 #endif
177 }
178 
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)
188 {
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);
190 }
191 
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)
202 {
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);
204 }
205 
223 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
224 
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)
226 {
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);
240  _mav_put_uint8_t(buf, 34, dgps_numch);
241 
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);
244 #else
245  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
246 #endif
247 #else
248  mavlink_gps2_raw_t packet;
249  packet.time_usec = time_usec;
250  packet.lat = lat;
251  packet.lon = lon;
252  packet.alt = alt;
253  packet.dgps_age = dgps_age;
254  packet.eph = eph;
255  packet.epv = epv;
256  packet.vel = vel;
257  packet.cog = cog;
258  packet.fix_type = fix_type;
260  packet.dgps_numch = dgps_numch;
261 
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);
264 #else
265  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
266 #endif
267 #endif
268 }
269 
270 #if MAVLINK_MSG_ID_GPS2_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
271 /*
272  This varient of _send() can be used to save stack space by re-using
273  memory from the receive buffer. The caller provides a
274  mavlink_message_t which is the size of a full mavlink message. This
275  is usually the receive buffer for the channel, and allows a reply to an
276  incoming message with minimum stack space usage.
277  */
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)
279 {
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);
293  _mav_put_uint8_t(buf, 34, dgps_numch);
294 
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);
297 #else
298  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
299 #endif
300 #else
301  mavlink_gps2_raw_t *packet = (mavlink_gps2_raw_t *)msgbuf;
302  packet->time_usec = time_usec;
303  packet->lat = lat;
304  packet->lon = lon;
305  packet->alt = alt;
306  packet->dgps_age = dgps_age;
307  packet->eph = eph;
308  packet->epv = epv;
309  packet->vel = vel;
310  packet->cog = cog;
311  packet->fix_type = fix_type;
313  packet->dgps_numch = dgps_numch;
314 
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);
317 #else
318  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
319 #endif
320 #endif
321 }
322 #endif
323 
324 #endif
325 
326 // MESSAGE GPS2_RAW UNPACKING
327 
328 
334 static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_t* msg)
335 {
336  return _MAV_RETURN_uint64_t(msg, 0);
337 }
338 
344 static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t* msg)
345 {
346  return _MAV_RETURN_uint8_t(msg, 32);
347 }
348 
354 static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg)
355 {
356  return _MAV_RETURN_int32_t(msg, 8);
357 }
358 
364 static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg)
365 {
366  return _MAV_RETURN_int32_t(msg, 12);
367 }
368 
374 static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg)
375 {
376  return _MAV_RETURN_int32_t(msg, 16);
377 }
378 
384 static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg)
385 {
386  return _MAV_RETURN_uint16_t(msg, 24);
387 }
388 
394 static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg)
395 {
396  return _MAV_RETURN_uint16_t(msg, 26);
397 }
398 
404 static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg)
405 {
406  return _MAV_RETURN_uint16_t(msg, 28);
407 }
408 
414 static inline uint16_t mavlink_msg_gps2_raw_get_cog(const mavlink_message_t* msg)
415 {
416  return _MAV_RETURN_uint16_t(msg, 30);
417 }
418 
424 static inline uint8_t mavlink_msg_gps2_raw_get_satellites_visible(const mavlink_message_t* msg)
425 {
426  return _MAV_RETURN_uint8_t(msg, 33);
427 }
428 
434 static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(const mavlink_message_t* msg)
435 {
436  return _MAV_RETURN_uint8_t(msg, 34);
437 }
438 
444 static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(const mavlink_message_t* msg)
445 {
446  return _MAV_RETURN_uint32_t(msg, 20);
447 }
448 
455 static inline void mavlink_msg_gps2_raw_decode(const mavlink_message_t* msg, mavlink_gps2_raw_t* gps2_raw)
456 {
457 #if MAVLINK_NEED_BYTE_SWAP
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);
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);
470 #else
471  memcpy(gps2_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS2_RAW_LEN);
472 #endif
473 }
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:244
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:140
#define _mav_put_uint64_t(buf, wire_offset, b)
Definition: protocol.h:149
#define _mav_put_int32_t(buf, wire_offset, b)
Definition: protocol.h:148
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:145
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:147


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:46