mavlink_msg_sim_state.h
Go to the documentation of this file.
1 // MESSAGE SIM_STATE PACKING
2 
3 #define MAVLINK_MSG_ID_SIM_STATE 108
4 
5 typedef struct __mavlink_sim_state_t
6 {
7  float q1; /*< True attitude quaternion component 1, w (1 in null-rotation)*/
8  float q2; /*< True attitude quaternion component 2, x (0 in null-rotation)*/
9  float q3; /*< True attitude quaternion component 3, y (0 in null-rotation)*/
10  float q4; /*< True attitude quaternion component 4, z (0 in null-rotation)*/
11  float roll; /*< Attitude roll expressed as Euler angles, not recommended except for human-readable outputs*/
12  float pitch; /*< Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs*/
13  float yaw; /*< Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs*/
14  float xacc; /*< X acceleration m/s/s*/
15  float yacc; /*< Y acceleration m/s/s*/
16  float zacc; /*< Z acceleration m/s/s*/
17  float xgyro; /*< Angular speed around X axis rad/s*/
18  float ygyro; /*< Angular speed around Y axis rad/s*/
19  float zgyro; /*< Angular speed around Z axis rad/s*/
20  float lat; /*< Latitude in degrees*/
21  float lon; /*< Longitude in degrees*/
22  float alt; /*< Altitude in meters*/
23  float std_dev_horz; /*< Horizontal position standard deviation*/
24  float std_dev_vert; /*< Vertical position standard deviation*/
25  float vn; /*< True velocity in m/s in NORTH direction in earth-fixed NED frame*/
26  float ve; /*< True velocity in m/s in EAST direction in earth-fixed NED frame*/
27  float vd; /*< True velocity in m/s in DOWN direction in earth-fixed NED frame*/
29 
30 #define MAVLINK_MSG_ID_SIM_STATE_LEN 84
31 #define MAVLINK_MSG_ID_108_LEN 84
32 
33 #define MAVLINK_MSG_ID_SIM_STATE_CRC 32
34 #define MAVLINK_MSG_ID_108_CRC 32
35 
36 
37 
38 #define MAVLINK_MESSAGE_INFO_SIM_STATE { \
39  "SIM_STATE", \
40  21, \
41  { { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sim_state_t, q1) }, \
42  { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sim_state_t, q2) }, \
43  { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sim_state_t, q3) }, \
44  { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sim_state_t, q4) }, \
45  { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sim_state_t, roll) }, \
46  { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sim_state_t, pitch) }, \
47  { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sim_state_t, yaw) }, \
48  { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sim_state_t, xacc) }, \
49  { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sim_state_t, yacc) }, \
50  { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sim_state_t, zacc) }, \
51  { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sim_state_t, xgyro) }, \
52  { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sim_state_t, ygyro) }, \
53  { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sim_state_t, zgyro) }, \
54  { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sim_state_t, lat) }, \
55  { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sim_state_t, lon) }, \
56  { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sim_state_t, alt) }, \
57  { "std_dev_horz", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sim_state_t, std_dev_horz) }, \
58  { "std_dev_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sim_state_t, std_dev_vert) }, \
59  { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sim_state_t, vn) }, \
60  { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sim_state_t, ve) }, \
61  { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sim_state_t, vd) }, \
62  } \
63 }
64 
65 
95 static inline uint16_t mavlink_msg_sim_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
96  float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd)
97 {
98 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
100  _mav_put_float(buf, 0, q1);
101  _mav_put_float(buf, 4, q2);
102  _mav_put_float(buf, 8, q3);
103  _mav_put_float(buf, 12, q4);
104  _mav_put_float(buf, 16, roll);
105  _mav_put_float(buf, 20, pitch);
106  _mav_put_float(buf, 24, yaw);
107  _mav_put_float(buf, 28, xacc);
108  _mav_put_float(buf, 32, yacc);
109  _mav_put_float(buf, 36, zacc);
110  _mav_put_float(buf, 40, xgyro);
111  _mav_put_float(buf, 44, ygyro);
112  _mav_put_float(buf, 48, zgyro);
113  _mav_put_float(buf, 52, lat);
114  _mav_put_float(buf, 56, lon);
115  _mav_put_float(buf, 60, alt);
116  _mav_put_float(buf, 64, std_dev_horz);
117  _mav_put_float(buf, 68, std_dev_vert);
118  _mav_put_float(buf, 72, vn);
119  _mav_put_float(buf, 76, ve);
120  _mav_put_float(buf, 80, vd);
121 
123 #else
124  mavlink_sim_state_t packet;
125  packet.q1 = q1;
126  packet.q2 = q2;
127  packet.q3 = q3;
128  packet.q4 = q4;
129  packet.roll = roll;
130  packet.pitch = pitch;
131  packet.yaw = yaw;
132  packet.xacc = xacc;
133  packet.yacc = yacc;
134  packet.zacc = zacc;
135  packet.xgyro = xgyro;
136  packet.ygyro = ygyro;
137  packet.zgyro = zgyro;
138  packet.lat = lat;
139  packet.lon = lon;
140  packet.alt = alt;
141  packet.std_dev_horz = std_dev_horz;
142  packet.std_dev_vert = std_dev_vert;
143  packet.vn = vn;
144  packet.ve = ve;
145  packet.vd = vd;
146 
148 #endif
149 
150  msg->msgid = MAVLINK_MSG_ID_SIM_STATE;
151 #if MAVLINK_CRC_EXTRA
153 #else
154  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIM_STATE_LEN);
155 #endif
156 }
157 
187 static inline uint16_t mavlink_msg_sim_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
188  mavlink_message_t* msg,
189  float q1,float q2,float q3,float q4,float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lon,float alt,float std_dev_horz,float std_dev_vert,float vn,float ve,float vd)
190 {
191 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
193  _mav_put_float(buf, 0, q1);
194  _mav_put_float(buf, 4, q2);
195  _mav_put_float(buf, 8, q3);
196  _mav_put_float(buf, 12, q4);
197  _mav_put_float(buf, 16, roll);
198  _mav_put_float(buf, 20, pitch);
199  _mav_put_float(buf, 24, yaw);
200  _mav_put_float(buf, 28, xacc);
201  _mav_put_float(buf, 32, yacc);
202  _mav_put_float(buf, 36, zacc);
203  _mav_put_float(buf, 40, xgyro);
204  _mav_put_float(buf, 44, ygyro);
205  _mav_put_float(buf, 48, zgyro);
206  _mav_put_float(buf, 52, lat);
207  _mav_put_float(buf, 56, lon);
208  _mav_put_float(buf, 60, alt);
209  _mav_put_float(buf, 64, std_dev_horz);
210  _mav_put_float(buf, 68, std_dev_vert);
211  _mav_put_float(buf, 72, vn);
212  _mav_put_float(buf, 76, ve);
213  _mav_put_float(buf, 80, vd);
214 
216 #else
217  mavlink_sim_state_t packet;
218  packet.q1 = q1;
219  packet.q2 = q2;
220  packet.q3 = q3;
221  packet.q4 = q4;
222  packet.roll = roll;
223  packet.pitch = pitch;
224  packet.yaw = yaw;
225  packet.xacc = xacc;
226  packet.yacc = yacc;
227  packet.zacc = zacc;
228  packet.xgyro = xgyro;
229  packet.ygyro = ygyro;
230  packet.zgyro = zgyro;
231  packet.lat = lat;
232  packet.lon = lon;
233  packet.alt = alt;
234  packet.std_dev_horz = std_dev_horz;
235  packet.std_dev_vert = std_dev_vert;
236  packet.vn = vn;
237  packet.ve = ve;
238  packet.vd = vd;
239 
241 #endif
242 
243  msg->msgid = MAVLINK_MSG_ID_SIM_STATE;
244 #if MAVLINK_CRC_EXTRA
246 #else
247  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIM_STATE_LEN);
248 #endif
249 }
250 
259 static inline uint16_t mavlink_msg_sim_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state)
260 {
261  return mavlink_msg_sim_state_pack(system_id, component_id, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd);
262 }
263 
273 static inline uint16_t mavlink_msg_sim_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state)
274 {
275  return mavlink_msg_sim_state_pack_chan(system_id, component_id, chan, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd);
276 }
277 
304 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
305 
306 static inline void mavlink_msg_sim_state_send(mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd)
307 {
308 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
310  _mav_put_float(buf, 0, q1);
311  _mav_put_float(buf, 4, q2);
312  _mav_put_float(buf, 8, q3);
313  _mav_put_float(buf, 12, q4);
314  _mav_put_float(buf, 16, roll);
315  _mav_put_float(buf, 20, pitch);
316  _mav_put_float(buf, 24, yaw);
317  _mav_put_float(buf, 28, xacc);
318  _mav_put_float(buf, 32, yacc);
319  _mav_put_float(buf, 36, zacc);
320  _mav_put_float(buf, 40, xgyro);
321  _mav_put_float(buf, 44, ygyro);
322  _mav_put_float(buf, 48, zgyro);
323  _mav_put_float(buf, 52, lat);
324  _mav_put_float(buf, 56, lon);
325  _mav_put_float(buf, 60, alt);
326  _mav_put_float(buf, 64, std_dev_horz);
327  _mav_put_float(buf, 68, std_dev_vert);
328  _mav_put_float(buf, 72, vn);
329  _mav_put_float(buf, 76, ve);
330  _mav_put_float(buf, 80, vd);
331 
332 #if MAVLINK_CRC_EXTRA
333  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
334 #else
335  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN);
336 #endif
337 #else
338  mavlink_sim_state_t packet;
339  packet.q1 = q1;
340  packet.q2 = q2;
341  packet.q3 = q3;
342  packet.q4 = q4;
343  packet.roll = roll;
344  packet.pitch = pitch;
345  packet.yaw = yaw;
346  packet.xacc = xacc;
347  packet.yacc = yacc;
348  packet.zacc = zacc;
349  packet.xgyro = xgyro;
350  packet.ygyro = ygyro;
351  packet.zgyro = zgyro;
352  packet.lat = lat;
353  packet.lon = lon;
354  packet.alt = alt;
355  packet.std_dev_horz = std_dev_horz;
356  packet.std_dev_vert = std_dev_vert;
357  packet.vn = vn;
358  packet.ve = ve;
359  packet.vd = vd;
360 
361 #if MAVLINK_CRC_EXTRA
362  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
363 #else
364  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_LEN);
365 #endif
366 #endif
367 }
368 
369 #if MAVLINK_MSG_ID_SIM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
370 /*
371  This varient of _send() can be used to save stack space by re-using
372  memory from the receive buffer. The caller provides a
373  mavlink_message_t which is the size of a full mavlink message. This
374  is usually the receive buffer for the channel, and allows a reply to an
375  incoming message with minimum stack space usage.
376  */
377 static inline void mavlink_msg_sim_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd)
378 {
379 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
380  char *buf = (char *)msgbuf;
381  _mav_put_float(buf, 0, q1);
382  _mav_put_float(buf, 4, q2);
383  _mav_put_float(buf, 8, q3);
384  _mav_put_float(buf, 12, q4);
385  _mav_put_float(buf, 16, roll);
386  _mav_put_float(buf, 20, pitch);
387  _mav_put_float(buf, 24, yaw);
388  _mav_put_float(buf, 28, xacc);
389  _mav_put_float(buf, 32, yacc);
390  _mav_put_float(buf, 36, zacc);
391  _mav_put_float(buf, 40, xgyro);
392  _mav_put_float(buf, 44, ygyro);
393  _mav_put_float(buf, 48, zgyro);
394  _mav_put_float(buf, 52, lat);
395  _mav_put_float(buf, 56, lon);
396  _mav_put_float(buf, 60, alt);
397  _mav_put_float(buf, 64, std_dev_horz);
398  _mav_put_float(buf, 68, std_dev_vert);
399  _mav_put_float(buf, 72, vn);
400  _mav_put_float(buf, 76, ve);
401  _mav_put_float(buf, 80, vd);
402 
403 #if MAVLINK_CRC_EXTRA
404  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
405 #else
406  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN);
407 #endif
408 #else
409  mavlink_sim_state_t *packet = (mavlink_sim_state_t *)msgbuf;
410  packet->q1 = q1;
411  packet->q2 = q2;
412  packet->q3 = q3;
413  packet->q4 = q4;
414  packet->roll = roll;
415  packet->pitch = pitch;
416  packet->yaw = yaw;
417  packet->xacc = xacc;
418  packet->yacc = yacc;
419  packet->zacc = zacc;
420  packet->xgyro = xgyro;
421  packet->ygyro = ygyro;
422  packet->zgyro = zgyro;
423  packet->lat = lat;
424  packet->lon = lon;
425  packet->alt = alt;
426  packet->std_dev_horz = std_dev_horz;
427  packet->std_dev_vert = std_dev_vert;
428  packet->vn = vn;
429  packet->ve = ve;
430  packet->vd = vd;
431 
432 #if MAVLINK_CRC_EXTRA
433  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
434 #else
435  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_LEN);
436 #endif
437 #endif
438 }
439 #endif
440 
441 #endif
442 
443 // MESSAGE SIM_STATE UNPACKING
444 
445 
451 static inline float mavlink_msg_sim_state_get_q1(const mavlink_message_t* msg)
452 {
453  return _MAV_RETURN_float(msg, 0);
454 }
455 
461 static inline float mavlink_msg_sim_state_get_q2(const mavlink_message_t* msg)
462 {
463  return _MAV_RETURN_float(msg, 4);
464 }
465 
471 static inline float mavlink_msg_sim_state_get_q3(const mavlink_message_t* msg)
472 {
473  return _MAV_RETURN_float(msg, 8);
474 }
475 
481 static inline float mavlink_msg_sim_state_get_q4(const mavlink_message_t* msg)
482 {
483  return _MAV_RETURN_float(msg, 12);
484 }
485 
491 static inline float mavlink_msg_sim_state_get_roll(const mavlink_message_t* msg)
492 {
493  return _MAV_RETURN_float(msg, 16);
494 }
495 
501 static inline float mavlink_msg_sim_state_get_pitch(const mavlink_message_t* msg)
502 {
503  return _MAV_RETURN_float(msg, 20);
504 }
505 
511 static inline float mavlink_msg_sim_state_get_yaw(const mavlink_message_t* msg)
512 {
513  return _MAV_RETURN_float(msg, 24);
514 }
515 
521 static inline float mavlink_msg_sim_state_get_xacc(const mavlink_message_t* msg)
522 {
523  return _MAV_RETURN_float(msg, 28);
524 }
525 
531 static inline float mavlink_msg_sim_state_get_yacc(const mavlink_message_t* msg)
532 {
533  return _MAV_RETURN_float(msg, 32);
534 }
535 
541 static inline float mavlink_msg_sim_state_get_zacc(const mavlink_message_t* msg)
542 {
543  return _MAV_RETURN_float(msg, 36);
544 }
545 
551 static inline float mavlink_msg_sim_state_get_xgyro(const mavlink_message_t* msg)
552 {
553  return _MAV_RETURN_float(msg, 40);
554 }
555 
561 static inline float mavlink_msg_sim_state_get_ygyro(const mavlink_message_t* msg)
562 {
563  return _MAV_RETURN_float(msg, 44);
564 }
565 
571 static inline float mavlink_msg_sim_state_get_zgyro(const mavlink_message_t* msg)
572 {
573  return _MAV_RETURN_float(msg, 48);
574 }
575 
581 static inline float mavlink_msg_sim_state_get_lat(const mavlink_message_t* msg)
582 {
583  return _MAV_RETURN_float(msg, 52);
584 }
585 
591 static inline float mavlink_msg_sim_state_get_lon(const mavlink_message_t* msg)
592 {
593  return _MAV_RETURN_float(msg, 56);
594 }
595 
601 static inline float mavlink_msg_sim_state_get_alt(const mavlink_message_t* msg)
602 {
603  return _MAV_RETURN_float(msg, 60);
604 }
605 
611 static inline float mavlink_msg_sim_state_get_std_dev_horz(const mavlink_message_t* msg)
612 {
613  return _MAV_RETURN_float(msg, 64);
614 }
615 
621 static inline float mavlink_msg_sim_state_get_std_dev_vert(const mavlink_message_t* msg)
622 {
623  return _MAV_RETURN_float(msg, 68);
624 }
625 
631 static inline float mavlink_msg_sim_state_get_vn(const mavlink_message_t* msg)
632 {
633  return _MAV_RETURN_float(msg, 72);
634 }
635 
641 static inline float mavlink_msg_sim_state_get_ve(const mavlink_message_t* msg)
642 {
643  return _MAV_RETURN_float(msg, 76);
644 }
645 
651 static inline float mavlink_msg_sim_state_get_vd(const mavlink_message_t* msg)
652 {
653  return _MAV_RETURN_float(msg, 80);
654 }
655 
662 static inline void mavlink_msg_sim_state_decode(const mavlink_message_t* msg, mavlink_sim_state_t* sim_state)
663 {
664 #if MAVLINK_NEED_BYTE_SWAP
665  sim_state->q1 = mavlink_msg_sim_state_get_q1(msg);
666  sim_state->q2 = mavlink_msg_sim_state_get_q2(msg);
667  sim_state->q3 = mavlink_msg_sim_state_get_q3(msg);
668  sim_state->q4 = mavlink_msg_sim_state_get_q4(msg);
669  sim_state->roll = mavlink_msg_sim_state_get_roll(msg);
670  sim_state->pitch = mavlink_msg_sim_state_get_pitch(msg);
671  sim_state->yaw = mavlink_msg_sim_state_get_yaw(msg);
672  sim_state->xacc = mavlink_msg_sim_state_get_xacc(msg);
673  sim_state->yacc = mavlink_msg_sim_state_get_yacc(msg);
674  sim_state->zacc = mavlink_msg_sim_state_get_zacc(msg);
675  sim_state->xgyro = mavlink_msg_sim_state_get_xgyro(msg);
676  sim_state->ygyro = mavlink_msg_sim_state_get_ygyro(msg);
677  sim_state->zgyro = mavlink_msg_sim_state_get_zgyro(msg);
678  sim_state->lat = mavlink_msg_sim_state_get_lat(msg);
679  sim_state->lon = mavlink_msg_sim_state_get_lon(msg);
680  sim_state->alt = mavlink_msg_sim_state_get_alt(msg);
683  sim_state->vn = mavlink_msg_sim_state_get_vn(msg);
684  sim_state->ve = mavlink_msg_sim_state_get_ve(msg);
685  sim_state->vd = mavlink_msg_sim_state_get_vd(msg);
686 #else
687  memcpy(sim_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SIM_STATE_LEN);
688 #endif
689 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:151


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