mavlink_msg_rosflight_gnss_full.h
Go to the documentation of this file.
1 // MESSAGE ROSFLIGHT_GNSS_FULL PACKING
2 
3 #define MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL 198
4 
6 {
7  uint64_t rosflight_timestamp; /*< */
8  uint32_t time_of_week; /*< */
9  uint32_t t_acc; /*< */
10  int32_t nano; /*< */
11  int32_t lon; /*< */
12  int32_t lat; /*< */
13  int32_t height; /*< */
14  int32_t height_msl; /*< */
15  uint32_t h_acc; /*< */
16  uint32_t v_acc; /*< */
17  int32_t vel_n; /*< */
18  int32_t vel_e; /*< */
19  int32_t vel_d; /*< */
20  int32_t g_speed; /*< */
21  int32_t head_mot; /*< */
22  uint32_t s_acc; /*< */
23  uint32_t head_acc; /*< */
24  uint16_t year; /*< */
25  uint16_t p_dop; /*< */
26  uint8_t month; /*< */
27  uint8_t day; /*< */
28  uint8_t hour; /*< */
29  uint8_t min; /*< */
30  uint8_t sec; /*< */
31  uint8_t valid; /*< */
32  uint8_t fix_type; /*< */
33  uint8_t num_sat; /*< */
35 
36 #define MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL_LEN 84
37 #define MAVLINK_MSG_ID_198_LEN 84
38 
39 #define MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL_CRC 204
40 #define MAVLINK_MSG_ID_198_CRC 204
41 
42 
43 
44 #define MAVLINK_MESSAGE_INFO_ROSFLIGHT_GNSS_FULL { \
45  "ROSFLIGHT_GNSS_FULL", \
46  27, \
47  { { "rosflight_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rosflight_gnss_full_t, rosflight_timestamp) }, \
48  { "time_of_week", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_rosflight_gnss_full_t, time_of_week) }, \
49  { "t_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_rosflight_gnss_full_t, t_acc) }, \
50  { "nano", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_rosflight_gnss_full_t, nano) }, \
51  { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_rosflight_gnss_full_t, lon) }, \
52  { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_rosflight_gnss_full_t, lat) }, \
53  { "height", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_rosflight_gnss_full_t, height) }, \
54  { "height_msl", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_rosflight_gnss_full_t, height_msl) }, \
55  { "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 36, offsetof(mavlink_rosflight_gnss_full_t, h_acc) }, \
56  { "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 40, offsetof(mavlink_rosflight_gnss_full_t, v_acc) }, \
57  { "vel_n", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_rosflight_gnss_full_t, vel_n) }, \
58  { "vel_e", NULL, MAVLINK_TYPE_INT32_T, 0, 48, offsetof(mavlink_rosflight_gnss_full_t, vel_e) }, \
59  { "vel_d", NULL, MAVLINK_TYPE_INT32_T, 0, 52, offsetof(mavlink_rosflight_gnss_full_t, vel_d) }, \
60  { "g_speed", NULL, MAVLINK_TYPE_INT32_T, 0, 56, offsetof(mavlink_rosflight_gnss_full_t, g_speed) }, \
61  { "head_mot", NULL, MAVLINK_TYPE_INT32_T, 0, 60, offsetof(mavlink_rosflight_gnss_full_t, head_mot) }, \
62  { "s_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 64, offsetof(mavlink_rosflight_gnss_full_t, s_acc) }, \
63  { "head_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 68, offsetof(mavlink_rosflight_gnss_full_t, head_acc) }, \
64  { "year", NULL, MAVLINK_TYPE_UINT16_T, 0, 72, offsetof(mavlink_rosflight_gnss_full_t, year) }, \
65  { "p_dop", NULL, MAVLINK_TYPE_UINT16_T, 0, 74, offsetof(mavlink_rosflight_gnss_full_t, p_dop) }, \
66  { "month", NULL, MAVLINK_TYPE_UINT8_T, 0, 76, offsetof(mavlink_rosflight_gnss_full_t, month) }, \
67  { "day", NULL, MAVLINK_TYPE_UINT8_T, 0, 77, offsetof(mavlink_rosflight_gnss_full_t, day) }, \
68  { "hour", NULL, MAVLINK_TYPE_UINT8_T, 0, 78, offsetof(mavlink_rosflight_gnss_full_t, hour) }, \
69  { "min", NULL, MAVLINK_TYPE_UINT8_T, 0, 79, offsetof(mavlink_rosflight_gnss_full_t, min) }, \
70  { "sec", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_rosflight_gnss_full_t, sec) }, \
71  { "valid", NULL, MAVLINK_TYPE_UINT8_T, 0, 81, offsetof(mavlink_rosflight_gnss_full_t, valid) }, \
72  { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_rosflight_gnss_full_t, fix_type) }, \
73  { "num_sat", NULL, MAVLINK_TYPE_UINT8_T, 0, 83, offsetof(mavlink_rosflight_gnss_full_t, num_sat) }, \
74  } \
75 }
76 
77 
113 static inline uint16_t mavlink_msg_rosflight_gnss_full_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
114  uint32_t time_of_week, uint16_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t valid, uint32_t t_acc, int32_t nano, uint8_t fix_type, uint8_t num_sat, int32_t lon, int32_t lat, int32_t height, int32_t height_msl, uint32_t h_acc, uint32_t v_acc, int32_t vel_n, int32_t vel_e, int32_t vel_d, int32_t g_speed, int32_t head_mot, uint32_t s_acc, uint32_t head_acc, uint16_t p_dop, uint64_t rosflight_timestamp)
115 {
116 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
118  _mav_put_uint64_t(buf, 0, rosflight_timestamp);
119  _mav_put_uint32_t(buf, 8, time_of_week);
120  _mav_put_uint32_t(buf, 12, t_acc);
121  _mav_put_int32_t(buf, 16, nano);
122  _mav_put_int32_t(buf, 20, lon);
123  _mav_put_int32_t(buf, 24, lat);
124  _mav_put_int32_t(buf, 28, height);
125  _mav_put_int32_t(buf, 32, height_msl);
126  _mav_put_uint32_t(buf, 36, h_acc);
127  _mav_put_uint32_t(buf, 40, v_acc);
128  _mav_put_int32_t(buf, 44, vel_n);
129  _mav_put_int32_t(buf, 48, vel_e);
130  _mav_put_int32_t(buf, 52, vel_d);
131  _mav_put_int32_t(buf, 56, g_speed);
132  _mav_put_int32_t(buf, 60, head_mot);
133  _mav_put_uint32_t(buf, 64, s_acc);
134  _mav_put_uint32_t(buf, 68, head_acc);
135  _mav_put_uint16_t(buf, 72, year);
136  _mav_put_uint16_t(buf, 74, p_dop);
137  _mav_put_uint8_t(buf, 76, month);
138  _mav_put_uint8_t(buf, 77, day);
139  _mav_put_uint8_t(buf, 78, hour);
140  _mav_put_uint8_t(buf, 79, min);
141  _mav_put_uint8_t(buf, 80, sec);
142  _mav_put_uint8_t(buf, 81, valid);
143  _mav_put_uint8_t(buf, 82, fix_type);
144  _mav_put_uint8_t(buf, 83, num_sat);
145 
147 #else
150  packet.time_of_week = time_of_week;
151  packet.t_acc = t_acc;
152  packet.nano = nano;
153  packet.lon = lon;
154  packet.lat = lat;
155  packet.height = height;
156  packet.height_msl = height_msl;
157  packet.h_acc = h_acc;
158  packet.v_acc = v_acc;
159  packet.vel_n = vel_n;
160  packet.vel_e = vel_e;
161  packet.vel_d = vel_d;
162  packet.g_speed = g_speed;
163  packet.head_mot = head_mot;
164  packet.s_acc = s_acc;
165  packet.head_acc = head_acc;
166  packet.year = year;
167  packet.p_dop = p_dop;
168  packet.month = month;
169  packet.day = day;
170  packet.hour = hour;
171  packet.min = min;
172  packet.sec = sec;
173  packet.valid = valid;
174  packet.fix_type = fix_type;
175  packet.num_sat = num_sat;
176 
178 #endif
179 
181 #if MAVLINK_CRC_EXTRA
183 #else
184  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL_LEN);
185 #endif
186 }
187 
223 static inline uint16_t mavlink_msg_rosflight_gnss_full_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
224  mavlink_message_t* msg,
225  uint32_t time_of_week,uint16_t year,uint8_t month,uint8_t day,uint8_t hour,uint8_t min,uint8_t sec,uint8_t valid,uint32_t t_acc,int32_t nano,uint8_t fix_type,uint8_t num_sat,int32_t lon,int32_t lat,int32_t height,int32_t height_msl,uint32_t h_acc,uint32_t v_acc,int32_t vel_n,int32_t vel_e,int32_t vel_d,int32_t g_speed,int32_t head_mot,uint32_t s_acc,uint32_t head_acc,uint16_t p_dop,uint64_t rosflight_timestamp)
226 {
227 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
229  _mav_put_uint64_t(buf, 0, rosflight_timestamp);
230  _mav_put_uint32_t(buf, 8, time_of_week);
231  _mav_put_uint32_t(buf, 12, t_acc);
232  _mav_put_int32_t(buf, 16, nano);
233  _mav_put_int32_t(buf, 20, lon);
234  _mav_put_int32_t(buf, 24, lat);
235  _mav_put_int32_t(buf, 28, height);
236  _mav_put_int32_t(buf, 32, height_msl);
237  _mav_put_uint32_t(buf, 36, h_acc);
238  _mav_put_uint32_t(buf, 40, v_acc);
239  _mav_put_int32_t(buf, 44, vel_n);
240  _mav_put_int32_t(buf, 48, vel_e);
241  _mav_put_int32_t(buf, 52, vel_d);
242  _mav_put_int32_t(buf, 56, g_speed);
243  _mav_put_int32_t(buf, 60, head_mot);
244  _mav_put_uint32_t(buf, 64, s_acc);
245  _mav_put_uint32_t(buf, 68, head_acc);
246  _mav_put_uint16_t(buf, 72, year);
247  _mav_put_uint16_t(buf, 74, p_dop);
248  _mav_put_uint8_t(buf, 76, month);
249  _mav_put_uint8_t(buf, 77, day);
250  _mav_put_uint8_t(buf, 78, hour);
251  _mav_put_uint8_t(buf, 79, min);
252  _mav_put_uint8_t(buf, 80, sec);
253  _mav_put_uint8_t(buf, 81, valid);
254  _mav_put_uint8_t(buf, 82, fix_type);
255  _mav_put_uint8_t(buf, 83, num_sat);
256 
258 #else
261  packet.time_of_week = time_of_week;
262  packet.t_acc = t_acc;
263  packet.nano = nano;
264  packet.lon = lon;
265  packet.lat = lat;
266  packet.height = height;
267  packet.height_msl = height_msl;
268  packet.h_acc = h_acc;
269  packet.v_acc = v_acc;
270  packet.vel_n = vel_n;
271  packet.vel_e = vel_e;
272  packet.vel_d = vel_d;
273  packet.g_speed = g_speed;
274  packet.head_mot = head_mot;
275  packet.s_acc = s_acc;
276  packet.head_acc = head_acc;
277  packet.year = year;
278  packet.p_dop = p_dop;
279  packet.month = month;
280  packet.day = day;
281  packet.hour = hour;
282  packet.min = min;
283  packet.sec = sec;
284  packet.valid = valid;
285  packet.fix_type = fix_type;
286  packet.num_sat = num_sat;
287 
289 #endif
290 
292 #if MAVLINK_CRC_EXTRA
294 #else
295  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL_LEN);
296 #endif
297 }
298 
307 static inline uint16_t mavlink_msg_rosflight_gnss_full_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rosflight_gnss_full_t* rosflight_gnss_full)
308 {
309  return mavlink_msg_rosflight_gnss_full_pack(system_id, component_id, msg, rosflight_gnss_full->time_of_week, rosflight_gnss_full->year, rosflight_gnss_full->month, rosflight_gnss_full->day, rosflight_gnss_full->hour, rosflight_gnss_full->min, rosflight_gnss_full->sec, rosflight_gnss_full->valid, rosflight_gnss_full->t_acc, rosflight_gnss_full->nano, rosflight_gnss_full->fix_type, rosflight_gnss_full->num_sat, rosflight_gnss_full->lon, rosflight_gnss_full->lat, rosflight_gnss_full->height, rosflight_gnss_full->height_msl, rosflight_gnss_full->h_acc, rosflight_gnss_full->v_acc, rosflight_gnss_full->vel_n, rosflight_gnss_full->vel_e, rosflight_gnss_full->vel_d, rosflight_gnss_full->g_speed, rosflight_gnss_full->head_mot, rosflight_gnss_full->s_acc, rosflight_gnss_full->head_acc, rosflight_gnss_full->p_dop, rosflight_gnss_full->rosflight_timestamp);
310 }
311 
321 static inline uint16_t mavlink_msg_rosflight_gnss_full_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rosflight_gnss_full_t* rosflight_gnss_full)
322 {
323  return mavlink_msg_rosflight_gnss_full_pack_chan(system_id, component_id, chan, msg, rosflight_gnss_full->time_of_week, rosflight_gnss_full->year, rosflight_gnss_full->month, rosflight_gnss_full->day, rosflight_gnss_full->hour, rosflight_gnss_full->min, rosflight_gnss_full->sec, rosflight_gnss_full->valid, rosflight_gnss_full->t_acc, rosflight_gnss_full->nano, rosflight_gnss_full->fix_type, rosflight_gnss_full->num_sat, rosflight_gnss_full->lon, rosflight_gnss_full->lat, rosflight_gnss_full->height, rosflight_gnss_full->height_msl, rosflight_gnss_full->h_acc, rosflight_gnss_full->v_acc, rosflight_gnss_full->vel_n, rosflight_gnss_full->vel_e, rosflight_gnss_full->vel_d, rosflight_gnss_full->g_speed, rosflight_gnss_full->head_mot, rosflight_gnss_full->s_acc, rosflight_gnss_full->head_acc, rosflight_gnss_full->p_dop, rosflight_gnss_full->rosflight_timestamp);
324 }
325 
358 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
359 
360 static inline void mavlink_msg_rosflight_gnss_full_send(mavlink_channel_t chan, uint32_t time_of_week, uint16_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t valid, uint32_t t_acc, int32_t nano, uint8_t fix_type, uint8_t num_sat, int32_t lon, int32_t lat, int32_t height, int32_t height_msl, uint32_t h_acc, uint32_t v_acc, int32_t vel_n, int32_t vel_e, int32_t vel_d, int32_t g_speed, int32_t head_mot, uint32_t s_acc, uint32_t head_acc, uint16_t p_dop, uint64_t rosflight_timestamp)
361 {
362 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
364  _mav_put_uint64_t(buf, 0, rosflight_timestamp);
366  _mav_put_uint32_t(buf, 12, t_acc);
367  _mav_put_int32_t(buf, 16, nano);
368  _mav_put_int32_t(buf, 20, lon);
369  _mav_put_int32_t(buf, 24, lat);
370  _mav_put_int32_t(buf, 28, height);
371  _mav_put_int32_t(buf, 32, height_msl);
372  _mav_put_uint32_t(buf, 36, h_acc);
373  _mav_put_uint32_t(buf, 40, v_acc);
374  _mav_put_int32_t(buf, 44, vel_n);
375  _mav_put_int32_t(buf, 48, vel_e);
376  _mav_put_int32_t(buf, 52, vel_d);
377  _mav_put_int32_t(buf, 56, g_speed);
378  _mav_put_int32_t(buf, 60, head_mot);
379  _mav_put_uint32_t(buf, 64, s_acc);
380  _mav_put_uint32_t(buf, 68, head_acc);
381  _mav_put_uint16_t(buf, 72, year);
382  _mav_put_uint16_t(buf, 74, p_dop);
383  _mav_put_uint8_t(buf, 76, month);
384  _mav_put_uint8_t(buf, 77, day);
385  _mav_put_uint8_t(buf, 78, hour);
386  _mav_put_uint8_t(buf, 79, min);
387  _mav_put_uint8_t(buf, 80, sec);
388  _mav_put_uint8_t(buf, 81, valid);
389  _mav_put_uint8_t(buf, 82, fix_type);
390  _mav_put_uint8_t(buf, 83, num_sat);
391 
392 #if MAVLINK_CRC_EXTRA
394 #else
395  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL, buf, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL_LEN);
396 #endif
397 #else
400  packet.time_of_week = time_of_week;
401  packet.t_acc = t_acc;
402  packet.nano = nano;
403  packet.lon = lon;
404  packet.lat = lat;
405  packet.height = height;
406  packet.height_msl = height_msl;
407  packet.h_acc = h_acc;
408  packet.v_acc = v_acc;
409  packet.vel_n = vel_n;
410  packet.vel_e = vel_e;
411  packet.vel_d = vel_d;
412  packet.g_speed = g_speed;
413  packet.head_mot = head_mot;
414  packet.s_acc = s_acc;
415  packet.head_acc = head_acc;
416  packet.year = year;
417  packet.p_dop = p_dop;
418  packet.month = month;
419  packet.day = day;
420  packet.hour = hour;
421  packet.min = min;
422  packet.sec = sec;
423  packet.valid = valid;
424  packet.fix_type = fix_type;
425  packet.num_sat = num_sat;
426 
427 #if MAVLINK_CRC_EXTRA
428  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL_LEN, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL_CRC);
429 #else
430  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL_LEN);
431 #endif
432 #endif
433 }
434 
435 #if MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
436 /*
437  This varient of _send() can be used to save stack space by re-using
438  memory from the receive buffer. The caller provides a
439  mavlink_message_t which is the size of a full mavlink message. This
440  is usually the receive buffer for the channel, and allows a reply to an
441  incoming message with minimum stack space usage.
442  */
443 static inline void mavlink_msg_rosflight_gnss_full_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_of_week, uint16_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t valid, uint32_t t_acc, int32_t nano, uint8_t fix_type, uint8_t num_sat, int32_t lon, int32_t lat, int32_t height, int32_t height_msl, uint32_t h_acc, uint32_t v_acc, int32_t vel_n, int32_t vel_e, int32_t vel_d, int32_t g_speed, int32_t head_mot, uint32_t s_acc, uint32_t head_acc, uint16_t p_dop, uint64_t rosflight_timestamp)
444 {
445 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
446  char *buf = (char *)msgbuf;
447  _mav_put_uint64_t(buf, 0, rosflight_timestamp);
449  _mav_put_uint32_t(buf, 12, t_acc);
450  _mav_put_int32_t(buf, 16, nano);
451  _mav_put_int32_t(buf, 20, lon);
452  _mav_put_int32_t(buf, 24, lat);
453  _mav_put_int32_t(buf, 28, height);
454  _mav_put_int32_t(buf, 32, height_msl);
455  _mav_put_uint32_t(buf, 36, h_acc);
456  _mav_put_uint32_t(buf, 40, v_acc);
457  _mav_put_int32_t(buf, 44, vel_n);
458  _mav_put_int32_t(buf, 48, vel_e);
459  _mav_put_int32_t(buf, 52, vel_d);
460  _mav_put_int32_t(buf, 56, g_speed);
461  _mav_put_int32_t(buf, 60, head_mot);
462  _mav_put_uint32_t(buf, 64, s_acc);
463  _mav_put_uint32_t(buf, 68, head_acc);
464  _mav_put_uint16_t(buf, 72, year);
465  _mav_put_uint16_t(buf, 74, p_dop);
466  _mav_put_uint8_t(buf, 76, month);
467  _mav_put_uint8_t(buf, 77, day);
468  _mav_put_uint8_t(buf, 78, hour);
469  _mav_put_uint8_t(buf, 79, min);
470  _mav_put_uint8_t(buf, 80, sec);
471  _mav_put_uint8_t(buf, 81, valid);
472  _mav_put_uint8_t(buf, 82, fix_type);
473  _mav_put_uint8_t(buf, 83, num_sat);
474 
475 #if MAVLINK_CRC_EXTRA
477 #else
478  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL, buf, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL_LEN);
479 #endif
480 #else
483  packet->time_of_week = time_of_week;
484  packet->t_acc = t_acc;
485  packet->nano = nano;
486  packet->lon = lon;
487  packet->lat = lat;
488  packet->height = height;
489  packet->height_msl = height_msl;
490  packet->h_acc = h_acc;
491  packet->v_acc = v_acc;
492  packet->vel_n = vel_n;
493  packet->vel_e = vel_e;
494  packet->vel_d = vel_d;
495  packet->g_speed = g_speed;
496  packet->head_mot = head_mot;
497  packet->s_acc = s_acc;
498  packet->head_acc = head_acc;
499  packet->year = year;
500  packet->p_dop = p_dop;
501  packet->month = month;
502  packet->day = day;
503  packet->hour = hour;
504  packet->min = min;
505  packet->sec = sec;
506  packet->valid = valid;
507  packet->fix_type = fix_type;
508  packet->num_sat = num_sat;
509 
510 #if MAVLINK_CRC_EXTRA
512 #else
513  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL_LEN);
514 #endif
515 #endif
516 }
517 #endif
518 
519 #endif
520 
521 // MESSAGE ROSFLIGHT_GNSS_FULL UNPACKING
522 
523 
529 static inline uint32_t mavlink_msg_rosflight_gnss_full_get_time_of_week(const mavlink_message_t* msg)
530 {
531  return _MAV_RETURN_uint32_t(msg, 8);
532 }
533 
539 static inline uint16_t mavlink_msg_rosflight_gnss_full_get_year(const mavlink_message_t* msg)
540 {
541  return _MAV_RETURN_uint16_t(msg, 72);
542 }
543 
549 static inline uint8_t mavlink_msg_rosflight_gnss_full_get_month(const mavlink_message_t* msg)
550 {
551  return _MAV_RETURN_uint8_t(msg, 76);
552 }
553 
559 static inline uint8_t mavlink_msg_rosflight_gnss_full_get_day(const mavlink_message_t* msg)
560 {
561  return _MAV_RETURN_uint8_t(msg, 77);
562 }
563 
569 static inline uint8_t mavlink_msg_rosflight_gnss_full_get_hour(const mavlink_message_t* msg)
570 {
571  return _MAV_RETURN_uint8_t(msg, 78);
572 }
573 
579 static inline uint8_t mavlink_msg_rosflight_gnss_full_get_min(const mavlink_message_t* msg)
580 {
581  return _MAV_RETURN_uint8_t(msg, 79);
582 }
583 
589 static inline uint8_t mavlink_msg_rosflight_gnss_full_get_sec(const mavlink_message_t* msg)
590 {
591  return _MAV_RETURN_uint8_t(msg, 80);
592 }
593 
599 static inline uint8_t mavlink_msg_rosflight_gnss_full_get_valid(const mavlink_message_t* msg)
600 {
601  return _MAV_RETURN_uint8_t(msg, 81);
602 }
603 
609 static inline uint32_t mavlink_msg_rosflight_gnss_full_get_t_acc(const mavlink_message_t* msg)
610 {
611  return _MAV_RETURN_uint32_t(msg, 12);
612 }
613 
619 static inline int32_t mavlink_msg_rosflight_gnss_full_get_nano(const mavlink_message_t* msg)
620 {
621  return _MAV_RETURN_int32_t(msg, 16);
622 }
623 
629 static inline uint8_t mavlink_msg_rosflight_gnss_full_get_fix_type(const mavlink_message_t* msg)
630 {
631  return _MAV_RETURN_uint8_t(msg, 82);
632 }
633 
639 static inline uint8_t mavlink_msg_rosflight_gnss_full_get_num_sat(const mavlink_message_t* msg)
640 {
641  return _MAV_RETURN_uint8_t(msg, 83);
642 }
643 
649 static inline int32_t mavlink_msg_rosflight_gnss_full_get_lon(const mavlink_message_t* msg)
650 {
651  return _MAV_RETURN_int32_t(msg, 20);
652 }
653 
659 static inline int32_t mavlink_msg_rosflight_gnss_full_get_lat(const mavlink_message_t* msg)
660 {
661  return _MAV_RETURN_int32_t(msg, 24);
662 }
663 
669 static inline int32_t mavlink_msg_rosflight_gnss_full_get_height(const mavlink_message_t* msg)
670 {
671  return _MAV_RETURN_int32_t(msg, 28);
672 }
673 
679 static inline int32_t mavlink_msg_rosflight_gnss_full_get_height_msl(const mavlink_message_t* msg)
680 {
681  return _MAV_RETURN_int32_t(msg, 32);
682 }
683 
689 static inline uint32_t mavlink_msg_rosflight_gnss_full_get_h_acc(const mavlink_message_t* msg)
690 {
691  return _MAV_RETURN_uint32_t(msg, 36);
692 }
693 
699 static inline uint32_t mavlink_msg_rosflight_gnss_full_get_v_acc(const mavlink_message_t* msg)
700 {
701  return _MAV_RETURN_uint32_t(msg, 40);
702 }
703 
709 static inline int32_t mavlink_msg_rosflight_gnss_full_get_vel_n(const mavlink_message_t* msg)
710 {
711  return _MAV_RETURN_int32_t(msg, 44);
712 }
713 
719 static inline int32_t mavlink_msg_rosflight_gnss_full_get_vel_e(const mavlink_message_t* msg)
720 {
721  return _MAV_RETURN_int32_t(msg, 48);
722 }
723 
729 static inline int32_t mavlink_msg_rosflight_gnss_full_get_vel_d(const mavlink_message_t* msg)
730 {
731  return _MAV_RETURN_int32_t(msg, 52);
732 }
733 
739 static inline int32_t mavlink_msg_rosflight_gnss_full_get_g_speed(const mavlink_message_t* msg)
740 {
741  return _MAV_RETURN_int32_t(msg, 56);
742 }
743 
749 static inline int32_t mavlink_msg_rosflight_gnss_full_get_head_mot(const mavlink_message_t* msg)
750 {
751  return _MAV_RETURN_int32_t(msg, 60);
752 }
753 
759 static inline uint32_t mavlink_msg_rosflight_gnss_full_get_s_acc(const mavlink_message_t* msg)
760 {
761  return _MAV_RETURN_uint32_t(msg, 64);
762 }
763 
769 static inline uint32_t mavlink_msg_rosflight_gnss_full_get_head_acc(const mavlink_message_t* msg)
770 {
771  return _MAV_RETURN_uint32_t(msg, 68);
772 }
773 
779 static inline uint16_t mavlink_msg_rosflight_gnss_full_get_p_dop(const mavlink_message_t* msg)
780 {
781  return _MAV_RETURN_uint16_t(msg, 74);
782 }
783 
789 static inline uint64_t mavlink_msg_rosflight_gnss_full_get_rosflight_timestamp(const mavlink_message_t* msg)
790 {
791  return _MAV_RETURN_uint64_t(msg, 0);
792 }
793 
800 static inline void mavlink_msg_rosflight_gnss_full_decode(const mavlink_message_t* msg, mavlink_rosflight_gnss_full_t* rosflight_gnss_full)
801 {
802 #if MAVLINK_NEED_BYTE_SWAP
805  rosflight_gnss_full->t_acc = mavlink_msg_rosflight_gnss_full_get_t_acc(msg);
806  rosflight_gnss_full->nano = mavlink_msg_rosflight_gnss_full_get_nano(msg);
807  rosflight_gnss_full->lon = mavlink_msg_rosflight_gnss_full_get_lon(msg);
808  rosflight_gnss_full->lat = mavlink_msg_rosflight_gnss_full_get_lat(msg);
809  rosflight_gnss_full->height = mavlink_msg_rosflight_gnss_full_get_height(msg);
811  rosflight_gnss_full->h_acc = mavlink_msg_rosflight_gnss_full_get_h_acc(msg);
812  rosflight_gnss_full->v_acc = mavlink_msg_rosflight_gnss_full_get_v_acc(msg);
813  rosflight_gnss_full->vel_n = mavlink_msg_rosflight_gnss_full_get_vel_n(msg);
814  rosflight_gnss_full->vel_e = mavlink_msg_rosflight_gnss_full_get_vel_e(msg);
815  rosflight_gnss_full->vel_d = mavlink_msg_rosflight_gnss_full_get_vel_d(msg);
816  rosflight_gnss_full->g_speed = mavlink_msg_rosflight_gnss_full_get_g_speed(msg);
817  rosflight_gnss_full->head_mot = mavlink_msg_rosflight_gnss_full_get_head_mot(msg);
818  rosflight_gnss_full->s_acc = mavlink_msg_rosflight_gnss_full_get_s_acc(msg);
819  rosflight_gnss_full->head_acc = mavlink_msg_rosflight_gnss_full_get_head_acc(msg);
820  rosflight_gnss_full->year = mavlink_msg_rosflight_gnss_full_get_year(msg);
821  rosflight_gnss_full->p_dop = mavlink_msg_rosflight_gnss_full_get_p_dop(msg);
822  rosflight_gnss_full->month = mavlink_msg_rosflight_gnss_full_get_month(msg);
823  rosflight_gnss_full->day = mavlink_msg_rosflight_gnss_full_get_day(msg);
824  rosflight_gnss_full->hour = mavlink_msg_rosflight_gnss_full_get_hour(msg);
825  rosflight_gnss_full->min = mavlink_msg_rosflight_gnss_full_get_min(msg);
826  rosflight_gnss_full->sec = mavlink_msg_rosflight_gnss_full_get_sec(msg);
827  rosflight_gnss_full->valid = mavlink_msg_rosflight_gnss_full_get_valid(msg);
828  rosflight_gnss_full->fix_type = mavlink_msg_rosflight_gnss_full_get_fix_type(msg);
829  rosflight_gnss_full->num_sat = mavlink_msg_rosflight_gnss_full_get_num_sat(msg);
830 #else
831  memcpy(rosflight_gnss_full, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL_LEN);
832 #endif
833 }
#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:47