mavlink_msg_hil_gps.h
Go to the documentation of this file.
1 // MESSAGE HIL_GPS PACKING
2 
3 #define MAVLINK_MSG_ID_HIL_GPS 113
4 
5 typedef struct __mavlink_hil_gps_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  uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535*/
12  uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535*/
13  uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: 65535*/
14  int16_t vn; /*< GPS velocity in cm/s in NORTH direction in earth-fixed NED frame*/
15  int16_t ve; /*< GPS velocity in cm/s in EAST direction in earth-fixed NED frame*/
16  int16_t vd; /*< GPS velocity in cm/s in DOWN direction in earth-fixed NED frame*/
17  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*/
18  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.*/
19  uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/
21 
22 #define MAVLINK_MSG_ID_HIL_GPS_LEN 36
23 #define MAVLINK_MSG_ID_113_LEN 36
24 
25 #define MAVLINK_MSG_ID_HIL_GPS_CRC 124
26 #define MAVLINK_MSG_ID_113_CRC 124
27 
28 
29 
30 #define MAVLINK_MESSAGE_INFO_HIL_GPS { \
31  "HIL_GPS", \
32  13, \
33  { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \
34  { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \
35  { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \
36  { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \
37  { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_gps_t, eph) }, \
38  { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_gps_t, epv) }, \
39  { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_gps_t, vel) }, \
40  { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_hil_gps_t, vn) }, \
41  { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \
42  { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \
43  { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \
44  { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \
45  { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \
46  } \
47 }
48 
49 
71 static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
72  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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible)
73 {
74 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
76  _mav_put_uint64_t(buf, 0, time_usec);
77  _mav_put_int32_t(buf, 8, lat);
78  _mav_put_int32_t(buf, 12, lon);
79  _mav_put_int32_t(buf, 16, alt);
80  _mav_put_uint16_t(buf, 20, eph);
81  _mav_put_uint16_t(buf, 22, epv);
82  _mav_put_uint16_t(buf, 24, vel);
83  _mav_put_int16_t(buf, 26, vn);
84  _mav_put_int16_t(buf, 28, ve);
85  _mav_put_int16_t(buf, 30, vd);
86  _mav_put_uint16_t(buf, 32, cog);
87  _mav_put_uint8_t(buf, 34, fix_type);
88  _mav_put_uint8_t(buf, 35, satellites_visible);
89 
91 #else
92  mavlink_hil_gps_t packet;
93  packet.time_usec = time_usec;
94  packet.lat = lat;
95  packet.lon = lon;
96  packet.alt = alt;
97  packet.eph = eph;
98  packet.epv = epv;
99  packet.vel = vel;
100  packet.vn = vn;
101  packet.ve = ve;
102  packet.vd = vd;
103  packet.cog = cog;
104  packet.fix_type = fix_type;
106 
107  memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
108 #endif
109 
110  msg->msgid = MAVLINK_MSG_ID_HIL_GPS;
111 #if MAVLINK_CRC_EXTRA
113 #else
114  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_LEN);
115 #endif
116 }
117 
139 static inline uint16_t mavlink_msg_hil_gps_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
140  mavlink_message_t* msg,
141  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,int16_t vn,int16_t ve,int16_t vd,uint16_t cog,uint8_t satellites_visible)
142 {
143 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
144  char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
145  _mav_put_uint64_t(buf, 0, time_usec);
146  _mav_put_int32_t(buf, 8, lat);
147  _mav_put_int32_t(buf, 12, lon);
148  _mav_put_int32_t(buf, 16, alt);
149  _mav_put_uint16_t(buf, 20, eph);
150  _mav_put_uint16_t(buf, 22, epv);
151  _mav_put_uint16_t(buf, 24, vel);
152  _mav_put_int16_t(buf, 26, vn);
153  _mav_put_int16_t(buf, 28, ve);
154  _mav_put_int16_t(buf, 30, vd);
155  _mav_put_uint16_t(buf, 32, cog);
156  _mav_put_uint8_t(buf, 34, fix_type);
157  _mav_put_uint8_t(buf, 35, satellites_visible);
158 
160 #else
161  mavlink_hil_gps_t packet;
162  packet.time_usec = time_usec;
163  packet.lat = lat;
164  packet.lon = lon;
165  packet.alt = alt;
166  packet.eph = eph;
167  packet.epv = epv;
168  packet.vel = vel;
169  packet.vn = vn;
170  packet.ve = ve;
171  packet.vd = vd;
172  packet.cog = cog;
173  packet.fix_type = fix_type;
175 
176  memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
177 #endif
178 
179  msg->msgid = MAVLINK_MSG_ID_HIL_GPS;
180 #if MAVLINK_CRC_EXTRA
181  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
182 #else
183  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_LEN);
184 #endif
185 }
186 
195 static inline uint16_t mavlink_msg_hil_gps_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps)
196 {
197  return mavlink_msg_hil_gps_pack(system_id, component_id, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible);
198 }
199 
209 static inline uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps)
210 {
211  return mavlink_msg_hil_gps_pack_chan(system_id, component_id, chan, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible);
212 }
213 
232 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
233 
234 static inline void mavlink_msg_hil_gps_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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible)
235 {
236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
237  char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
238  _mav_put_uint64_t(buf, 0, time_usec);
239  _mav_put_int32_t(buf, 8, lat);
240  _mav_put_int32_t(buf, 12, lon);
241  _mav_put_int32_t(buf, 16, alt);
242  _mav_put_uint16_t(buf, 20, eph);
243  _mav_put_uint16_t(buf, 22, epv);
244  _mav_put_uint16_t(buf, 24, vel);
245  _mav_put_int16_t(buf, 26, vn);
246  _mav_put_int16_t(buf, 28, ve);
247  _mav_put_int16_t(buf, 30, vd);
248  _mav_put_uint16_t(buf, 32, cog);
249  _mav_put_uint8_t(buf, 34, fix_type);
250  _mav_put_uint8_t(buf, 35, satellites_visible);
251 
252 #if MAVLINK_CRC_EXTRA
253  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
254 #else
255  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
256 #endif
257 #else
258  mavlink_hil_gps_t packet;
259  packet.time_usec = time_usec;
260  packet.lat = lat;
261  packet.lon = lon;
262  packet.alt = alt;
263  packet.eph = eph;
264  packet.epv = epv;
265  packet.vel = vel;
266  packet.vn = vn;
267  packet.ve = ve;
268  packet.vd = vd;
269  packet.cog = cog;
270  packet.fix_type = fix_type;
272 
273 #if MAVLINK_CRC_EXTRA
274  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
275 #else
276  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
277 #endif
278 #endif
279 }
280 
281 #if MAVLINK_MSG_ID_HIL_GPS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
282 /*
283  This varient of _send() can be used to save stack space by re-using
284  memory from the receive buffer. The caller provides a
285  mavlink_message_t which is the size of a full mavlink message. This
286  is usually the receive buffer for the channel, and allows a reply to an
287  incoming message with minimum stack space usage.
288  */
289 static inline void mavlink_msg_hil_gps_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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible)
290 {
291 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
292  char *buf = (char *)msgbuf;
293  _mav_put_uint64_t(buf, 0, time_usec);
294  _mav_put_int32_t(buf, 8, lat);
295  _mav_put_int32_t(buf, 12, lon);
296  _mav_put_int32_t(buf, 16, alt);
297  _mav_put_uint16_t(buf, 20, eph);
298  _mav_put_uint16_t(buf, 22, epv);
299  _mav_put_uint16_t(buf, 24, vel);
300  _mav_put_int16_t(buf, 26, vn);
301  _mav_put_int16_t(buf, 28, ve);
302  _mav_put_int16_t(buf, 30, vd);
303  _mav_put_uint16_t(buf, 32, cog);
304  _mav_put_uint8_t(buf, 34, fix_type);
305  _mav_put_uint8_t(buf, 35, satellites_visible);
306 
307 #if MAVLINK_CRC_EXTRA
308  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
309 #else
310  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
311 #endif
312 #else
313  mavlink_hil_gps_t *packet = (mavlink_hil_gps_t *)msgbuf;
314  packet->time_usec = time_usec;
315  packet->lat = lat;
316  packet->lon = lon;
317  packet->alt = alt;
318  packet->eph = eph;
319  packet->epv = epv;
320  packet->vel = vel;
321  packet->vn = vn;
322  packet->ve = ve;
323  packet->vd = vd;
324  packet->cog = cog;
325  packet->fix_type = fix_type;
327 
328 #if MAVLINK_CRC_EXTRA
329  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
330 #else
331  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
332 #endif
333 #endif
334 }
335 #endif
336 
337 #endif
338 
339 // MESSAGE HIL_GPS UNPACKING
340 
341 
347 static inline uint64_t mavlink_msg_hil_gps_get_time_usec(const mavlink_message_t* msg)
348 {
349  return _MAV_RETURN_uint64_t(msg, 0);
350 }
351 
357 static inline uint8_t mavlink_msg_hil_gps_get_fix_type(const mavlink_message_t* msg)
358 {
359  return _MAV_RETURN_uint8_t(msg, 34);
360 }
361 
367 static inline int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t* msg)
368 {
369  return _MAV_RETURN_int32_t(msg, 8);
370 }
371 
377 static inline int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t* msg)
378 {
379  return _MAV_RETURN_int32_t(msg, 12);
380 }
381 
387 static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg)
388 {
389  return _MAV_RETURN_int32_t(msg, 16);
390 }
391 
397 static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg)
398 {
399  return _MAV_RETURN_uint16_t(msg, 20);
400 }
401 
407 static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg)
408 {
409  return _MAV_RETURN_uint16_t(msg, 22);
410 }
411 
417 static inline uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t* msg)
418 {
419  return _MAV_RETURN_uint16_t(msg, 24);
420 }
421 
427 static inline int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t* msg)
428 {
429  return _MAV_RETURN_int16_t(msg, 26);
430 }
431 
437 static inline int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t* msg)
438 {
439  return _MAV_RETURN_int16_t(msg, 28);
440 }
441 
447 static inline int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t* msg)
448 {
449  return _MAV_RETURN_int16_t(msg, 30);
450 }
451 
457 static inline uint16_t mavlink_msg_hil_gps_get_cog(const mavlink_message_t* msg)
458 {
459  return _MAV_RETURN_uint16_t(msg, 32);
460 }
461 
467 static inline uint8_t mavlink_msg_hil_gps_get_satellites_visible(const mavlink_message_t* msg)
468 {
469  return _MAV_RETURN_uint8_t(msg, 35);
470 }
471 
478 static inline void mavlink_msg_hil_gps_decode(const mavlink_message_t* msg, mavlink_hil_gps_t* hil_gps)
479 {
480 #if MAVLINK_NEED_BYTE_SWAP
482  hil_gps->lat = mavlink_msg_hil_gps_get_lat(msg);
483  hil_gps->lon = mavlink_msg_hil_gps_get_lon(msg);
484  hil_gps->alt = mavlink_msg_hil_gps_get_alt(msg);
485  hil_gps->eph = mavlink_msg_hil_gps_get_eph(msg);
486  hil_gps->epv = mavlink_msg_hil_gps_get_epv(msg);
487  hil_gps->vel = mavlink_msg_hil_gps_get_vel(msg);
488  hil_gps->vn = mavlink_msg_hil_gps_get_vn(msg);
489  hil_gps->ve = mavlink_msg_hil_gps_get_ve(msg);
490  hil_gps->vd = mavlink_msg_hil_gps_get_vd(msg);
491  hil_gps->cog = mavlink_msg_hil_gps_get_cog(msg);
494 #else
495  memcpy(hil_gps, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_GPS_LEN);
496 #endif
497 }
#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_int16_t(buf, wire_offset, b)
Definition: protocol.h:146


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