RflySimSDK v3.05
RflySimSDK说明文档
载入中...
搜索中...
未找到
mavlink_msg_sim_state.h
1#pragma once
2// MESSAGE SIM_STATE PACKING
3
4#define MAVLINK_MSG_ID_SIM_STATE 108
5
6MAVPACKED(
7typedef struct __mavlink_sim_state_t {
8 float q1; /*< True attitude quaternion component 1, w (1 in null-rotation)*/
9 float q2; /*< True attitude quaternion component 2, x (0 in null-rotation)*/
10 float q3; /*< True attitude quaternion component 3, y (0 in null-rotation)*/
11 float q4; /*< True attitude quaternion component 4, z (0 in null-rotation)*/
12 float roll; /*< Attitude roll expressed as Euler angles, not recommended except for human-readable outputs*/
13 float pitch; /*< Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs*/
14 float yaw; /*< Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs*/
15 float xacc; /*< X acceleration m/s/s*/
16 float yacc; /*< Y acceleration m/s/s*/
17 float zacc; /*< Z acceleration m/s/s*/
18 float xgyro; /*< Angular speed around X axis rad/s*/
19 float ygyro; /*< Angular speed around Y axis rad/s*/
20 float zgyro; /*< Angular speed around Z axis rad/s*/
21 float lat; /*< Latitude in degrees*/
22 float lon; /*< Longitude in degrees*/
23 float alt; /*< Altitude in meters*/
24 float std_dev_horz; /*< Horizontal position standard deviation*/
25 float std_dev_vert; /*< Vertical position standard deviation*/
26 float vn; /*< True velocity in m/s in NORTH direction in earth-fixed NED frame*/
27 float ve; /*< True velocity in m/s in EAST direction in earth-fixed NED frame*/
28 float vd; /*< True velocity in m/s in DOWN direction in earth-fixed NED frame*/
29}) mavlink_sim_state_t;
30
31#define MAVLINK_MSG_ID_SIM_STATE_LEN 84
32#define MAVLINK_MSG_ID_SIM_STATE_MIN_LEN 84
33#define MAVLINK_MSG_ID_108_LEN 84
34#define MAVLINK_MSG_ID_108_MIN_LEN 84
35
36#define MAVLINK_MSG_ID_SIM_STATE_CRC 32
37#define MAVLINK_MSG_ID_108_CRC 32
38
39
40
41#if MAVLINK_COMMAND_24BIT
42#define MAVLINK_MESSAGE_INFO_SIM_STATE { \
43 108, \
44 "SIM_STATE", \
45 21, \
46 { { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sim_state_t, q1) }, \
47 { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sim_state_t, q2) }, \
48 { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sim_state_t, q3) }, \
49 { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sim_state_t, q4) }, \
50 { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sim_state_t, roll) }, \
51 { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sim_state_t, pitch) }, \
52 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sim_state_t, yaw) }, \
53 { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sim_state_t, xacc) }, \
54 { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sim_state_t, yacc) }, \
55 { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sim_state_t, zacc) }, \
56 { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sim_state_t, xgyro) }, \
57 { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sim_state_t, ygyro) }, \
58 { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sim_state_t, zgyro) }, \
59 { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sim_state_t, lat) }, \
60 { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sim_state_t, lon) }, \
61 { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sim_state_t, alt) }, \
62 { "std_dev_horz", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sim_state_t, std_dev_horz) }, \
63 { "std_dev_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sim_state_t, std_dev_vert) }, \
64 { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sim_state_t, vn) }, \
65 { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sim_state_t, ve) }, \
66 { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sim_state_t, vd) }, \
67 } \
68}
69#else
70#define MAVLINK_MESSAGE_INFO_SIM_STATE { \
71 "SIM_STATE", \
72 21, \
73 { { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sim_state_t, q1) }, \
74 { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sim_state_t, q2) }, \
75 { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sim_state_t, q3) }, \
76 { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sim_state_t, q4) }, \
77 { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sim_state_t, roll) }, \
78 { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sim_state_t, pitch) }, \
79 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sim_state_t, yaw) }, \
80 { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sim_state_t, xacc) }, \
81 { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sim_state_t, yacc) }, \
82 { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sim_state_t, zacc) }, \
83 { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sim_state_t, xgyro) }, \
84 { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sim_state_t, ygyro) }, \
85 { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sim_state_t, zgyro) }, \
86 { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sim_state_t, lat) }, \
87 { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sim_state_t, lon) }, \
88 { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sim_state_t, alt) }, \
89 { "std_dev_horz", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sim_state_t, std_dev_horz) }, \
90 { "std_dev_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sim_state_t, std_dev_vert) }, \
91 { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sim_state_t, vn) }, \
92 { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sim_state_t, ve) }, \
93 { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sim_state_t, vd) }, \
94 } \
95}
96#endif
97
127static inline uint16_t mavlink_msg_sim_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
128 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)
129{
130#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
131 char buf[MAVLINK_MSG_ID_SIM_STATE_LEN];
132 _mav_put_float(buf, 0, q1);
133 _mav_put_float(buf, 4, q2);
134 _mav_put_float(buf, 8, q3);
135 _mav_put_float(buf, 12, q4);
136 _mav_put_float(buf, 16, roll);
137 _mav_put_float(buf, 20, pitch);
138 _mav_put_float(buf, 24, yaw);
139 _mav_put_float(buf, 28, xacc);
140 _mav_put_float(buf, 32, yacc);
141 _mav_put_float(buf, 36, zacc);
142 _mav_put_float(buf, 40, xgyro);
143 _mav_put_float(buf, 44, ygyro);
144 _mav_put_float(buf, 48, zgyro);
145 _mav_put_float(buf, 52, lat);
146 _mav_put_float(buf, 56, lon);
147 _mav_put_float(buf, 60, alt);
148 _mav_put_float(buf, 64, std_dev_horz);
149 _mav_put_float(buf, 68, std_dev_vert);
150 _mav_put_float(buf, 72, vn);
151 _mav_put_float(buf, 76, ve);
152 _mav_put_float(buf, 80, vd);
153
154 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN);
155#else
156 mavlink_sim_state_t packet;
157 packet.q1 = q1;
158 packet.q2 = q2;
159 packet.q3 = q3;
160 packet.q4 = q4;
161 packet.roll = roll;
162 packet.pitch = pitch;
163 packet.yaw = yaw;
164 packet.xacc = xacc;
165 packet.yacc = yacc;
166 packet.zacc = zacc;
167 packet.xgyro = xgyro;
168 packet.ygyro = ygyro;
169 packet.zgyro = zgyro;
170 packet.lat = lat;
171 packet.lon = lon;
172 packet.alt = alt;
173 packet.std_dev_horz = std_dev_horz;
174 packet.std_dev_vert = std_dev_vert;
175 packet.vn = vn;
176 packet.ve = ve;
177 packet.vd = vd;
178
179 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN);
180#endif
181
182 msg->msgid = MAVLINK_MSG_ID_SIM_STATE;
183 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
184}
185
215static inline uint16_t mavlink_msg_sim_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
216 mavlink_message_t* msg,
217 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)
218{
219#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
220 char buf[MAVLINK_MSG_ID_SIM_STATE_LEN];
221 _mav_put_float(buf, 0, q1);
222 _mav_put_float(buf, 4, q2);
223 _mav_put_float(buf, 8, q3);
224 _mav_put_float(buf, 12, q4);
225 _mav_put_float(buf, 16, roll);
226 _mav_put_float(buf, 20, pitch);
227 _mav_put_float(buf, 24, yaw);
228 _mav_put_float(buf, 28, xacc);
229 _mav_put_float(buf, 32, yacc);
230 _mav_put_float(buf, 36, zacc);
231 _mav_put_float(buf, 40, xgyro);
232 _mav_put_float(buf, 44, ygyro);
233 _mav_put_float(buf, 48, zgyro);
234 _mav_put_float(buf, 52, lat);
235 _mav_put_float(buf, 56, lon);
236 _mav_put_float(buf, 60, alt);
237 _mav_put_float(buf, 64, std_dev_horz);
238 _mav_put_float(buf, 68, std_dev_vert);
239 _mav_put_float(buf, 72, vn);
240 _mav_put_float(buf, 76, ve);
241 _mav_put_float(buf, 80, vd);
242
243 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN);
244#else
245 mavlink_sim_state_t packet;
246 packet.q1 = q1;
247 packet.q2 = q2;
248 packet.q3 = q3;
249 packet.q4 = q4;
250 packet.roll = roll;
251 packet.pitch = pitch;
252 packet.yaw = yaw;
253 packet.xacc = xacc;
254 packet.yacc = yacc;
255 packet.zacc = zacc;
256 packet.xgyro = xgyro;
257 packet.ygyro = ygyro;
258 packet.zgyro = zgyro;
259 packet.lat = lat;
260 packet.lon = lon;
261 packet.alt = alt;
262 packet.std_dev_horz = std_dev_horz;
263 packet.std_dev_vert = std_dev_vert;
264 packet.vn = vn;
265 packet.ve = ve;
266 packet.vd = vd;
267
268 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN);
269#endif
270
271 msg->msgid = MAVLINK_MSG_ID_SIM_STATE;
272 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
273}
274
283static 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)
284{
285 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);
286}
287
297static 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)
298{
299 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);
300}
301
328#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
329
330static 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)
331{
332#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
333 char buf[MAVLINK_MSG_ID_SIM_STATE_LEN];
334 _mav_put_float(buf, 0, q1);
335 _mav_put_float(buf, 4, q2);
336 _mav_put_float(buf, 8, q3);
337 _mav_put_float(buf, 12, q4);
338 _mav_put_float(buf, 16, roll);
339 _mav_put_float(buf, 20, pitch);
340 _mav_put_float(buf, 24, yaw);
341 _mav_put_float(buf, 28, xacc);
342 _mav_put_float(buf, 32, yacc);
343 _mav_put_float(buf, 36, zacc);
344 _mav_put_float(buf, 40, xgyro);
345 _mav_put_float(buf, 44, ygyro);
346 _mav_put_float(buf, 48, zgyro);
347 _mav_put_float(buf, 52, lat);
348 _mav_put_float(buf, 56, lon);
349 _mav_put_float(buf, 60, alt);
350 _mav_put_float(buf, 64, std_dev_horz);
351 _mav_put_float(buf, 68, std_dev_vert);
352 _mav_put_float(buf, 72, vn);
353 _mav_put_float(buf, 76, ve);
354 _mav_put_float(buf, 80, vd);
355
356 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
357#else
358 mavlink_sim_state_t packet;
359 packet.q1 = q1;
360 packet.q2 = q2;
361 packet.q3 = q3;
362 packet.q4 = q4;
363 packet.roll = roll;
364 packet.pitch = pitch;
365 packet.yaw = yaw;
366 packet.xacc = xacc;
367 packet.yacc = yacc;
368 packet.zacc = zacc;
369 packet.xgyro = xgyro;
370 packet.ygyro = ygyro;
371 packet.zgyro = zgyro;
372 packet.lat = lat;
373 packet.lon = lon;
374 packet.alt = alt;
375 packet.std_dev_horz = std_dev_horz;
376 packet.std_dev_vert = std_dev_vert;
377 packet.vn = vn;
378 packet.ve = ve;
379 packet.vd = vd;
380
381 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
382#endif
383}
384
390static inline void mavlink_msg_sim_state_send_struct(mavlink_channel_t chan, const mavlink_sim_state_t* sim_state)
391{
392#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
393 mavlink_msg_sim_state_send(chan, 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);
394#else
395 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)sim_state, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
396#endif
397}
398
399#if MAVLINK_MSG_ID_SIM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
400/*
401 This varient of _send() can be used to save stack space by re-using
402 memory from the receive buffer. The caller provides a
403 mavlink_message_t which is the size of a full mavlink message. This
404 is usually the receive buffer for the channel, and allows a reply to an
405 incoming message with minimum stack space usage.
406 */
407static 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)
408{
409#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
410 char *buf = (char *)msgbuf;
411 _mav_put_float(buf, 0, q1);
412 _mav_put_float(buf, 4, q2);
413 _mav_put_float(buf, 8, q3);
414 _mav_put_float(buf, 12, q4);
415 _mav_put_float(buf, 16, roll);
416 _mav_put_float(buf, 20, pitch);
417 _mav_put_float(buf, 24, yaw);
418 _mav_put_float(buf, 28, xacc);
419 _mav_put_float(buf, 32, yacc);
420 _mav_put_float(buf, 36, zacc);
421 _mav_put_float(buf, 40, xgyro);
422 _mav_put_float(buf, 44, ygyro);
423 _mav_put_float(buf, 48, zgyro);
424 _mav_put_float(buf, 52, lat);
425 _mav_put_float(buf, 56, lon);
426 _mav_put_float(buf, 60, alt);
427 _mav_put_float(buf, 64, std_dev_horz);
428 _mav_put_float(buf, 68, std_dev_vert);
429 _mav_put_float(buf, 72, vn);
430 _mav_put_float(buf, 76, ve);
431 _mav_put_float(buf, 80, vd);
432
433 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
434#else
435 mavlink_sim_state_t *packet = (mavlink_sim_state_t *)msgbuf;
436 packet->q1 = q1;
437 packet->q2 = q2;
438 packet->q3 = q3;
439 packet->q4 = q4;
440 packet->roll = roll;
441 packet->pitch = pitch;
442 packet->yaw = yaw;
443 packet->xacc = xacc;
444 packet->yacc = yacc;
445 packet->zacc = zacc;
446 packet->xgyro = xgyro;
447 packet->ygyro = ygyro;
448 packet->zgyro = zgyro;
449 packet->lat = lat;
450 packet->lon = lon;
451 packet->alt = alt;
452 packet->std_dev_horz = std_dev_horz;
453 packet->std_dev_vert = std_dev_vert;
454 packet->vn = vn;
455 packet->ve = ve;
456 packet->vd = vd;
457
458 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
459#endif
460}
461#endif
462
463#endif
464
465// MESSAGE SIM_STATE UNPACKING
466
467
473static inline float mavlink_msg_sim_state_get_q1(const mavlink_message_t* msg)
474{
475 return _MAV_RETURN_float(msg, 0);
476}
477
483static inline float mavlink_msg_sim_state_get_q2(const mavlink_message_t* msg)
484{
485 return _MAV_RETURN_float(msg, 4);
486}
487
493static inline float mavlink_msg_sim_state_get_q3(const mavlink_message_t* msg)
494{
495 return _MAV_RETURN_float(msg, 8);
496}
497
503static inline float mavlink_msg_sim_state_get_q4(const mavlink_message_t* msg)
504{
505 return _MAV_RETURN_float(msg, 12);
506}
507
513static inline float mavlink_msg_sim_state_get_roll(const mavlink_message_t* msg)
514{
515 return _MAV_RETURN_float(msg, 16);
516}
517
523static inline float mavlink_msg_sim_state_get_pitch(const mavlink_message_t* msg)
524{
525 return _MAV_RETURN_float(msg, 20);
526}
527
533static inline float mavlink_msg_sim_state_get_yaw(const mavlink_message_t* msg)
534{
535 return _MAV_RETURN_float(msg, 24);
536}
537
543static inline float mavlink_msg_sim_state_get_xacc(const mavlink_message_t* msg)
544{
545 return _MAV_RETURN_float(msg, 28);
546}
547
553static inline float mavlink_msg_sim_state_get_yacc(const mavlink_message_t* msg)
554{
555 return _MAV_RETURN_float(msg, 32);
556}
557
563static inline float mavlink_msg_sim_state_get_zacc(const mavlink_message_t* msg)
564{
565 return _MAV_RETURN_float(msg, 36);
566}
567
573static inline float mavlink_msg_sim_state_get_xgyro(const mavlink_message_t* msg)
574{
575 return _MAV_RETURN_float(msg, 40);
576}
577
583static inline float mavlink_msg_sim_state_get_ygyro(const mavlink_message_t* msg)
584{
585 return _MAV_RETURN_float(msg, 44);
586}
587
593static inline float mavlink_msg_sim_state_get_zgyro(const mavlink_message_t* msg)
594{
595 return _MAV_RETURN_float(msg, 48);
596}
597
603static inline float mavlink_msg_sim_state_get_lat(const mavlink_message_t* msg)
604{
605 return _MAV_RETURN_float(msg, 52);
606}
607
613static inline float mavlink_msg_sim_state_get_lon(const mavlink_message_t* msg)
614{
615 return _MAV_RETURN_float(msg, 56);
616}
617
623static inline float mavlink_msg_sim_state_get_alt(const mavlink_message_t* msg)
624{
625 return _MAV_RETURN_float(msg, 60);
626}
627
633static inline float mavlink_msg_sim_state_get_std_dev_horz(const mavlink_message_t* msg)
634{
635 return _MAV_RETURN_float(msg, 64);
636}
637
643static inline float mavlink_msg_sim_state_get_std_dev_vert(const mavlink_message_t* msg)
644{
645 return _MAV_RETURN_float(msg, 68);
646}
647
653static inline float mavlink_msg_sim_state_get_vn(const mavlink_message_t* msg)
654{
655 return _MAV_RETURN_float(msg, 72);
656}
657
663static inline float mavlink_msg_sim_state_get_ve(const mavlink_message_t* msg)
664{
665 return _MAV_RETURN_float(msg, 76);
666}
667
673static inline float mavlink_msg_sim_state_get_vd(const mavlink_message_t* msg)
674{
675 return _MAV_RETURN_float(msg, 80);
676}
677
684static inline void mavlink_msg_sim_state_decode(const mavlink_message_t* msg, mavlink_sim_state_t* sim_state)
685{
686#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
687 sim_state->q1 = mavlink_msg_sim_state_get_q1(msg);
688 sim_state->q2 = mavlink_msg_sim_state_get_q2(msg);
689 sim_state->q3 = mavlink_msg_sim_state_get_q3(msg);
690 sim_state->q4 = mavlink_msg_sim_state_get_q4(msg);
691 sim_state->roll = mavlink_msg_sim_state_get_roll(msg);
692 sim_state->pitch = mavlink_msg_sim_state_get_pitch(msg);
693 sim_state->yaw = mavlink_msg_sim_state_get_yaw(msg);
694 sim_state->xacc = mavlink_msg_sim_state_get_xacc(msg);
695 sim_state->yacc = mavlink_msg_sim_state_get_yacc(msg);
696 sim_state->zacc = mavlink_msg_sim_state_get_zacc(msg);
697 sim_state->xgyro = mavlink_msg_sim_state_get_xgyro(msg);
698 sim_state->ygyro = mavlink_msg_sim_state_get_ygyro(msg);
699 sim_state->zgyro = mavlink_msg_sim_state_get_zgyro(msg);
700 sim_state->lat = mavlink_msg_sim_state_get_lat(msg);
701 sim_state->lon = mavlink_msg_sim_state_get_lon(msg);
702 sim_state->alt = mavlink_msg_sim_state_get_alt(msg);
703 sim_state->std_dev_horz = mavlink_msg_sim_state_get_std_dev_horz(msg);
704 sim_state->std_dev_vert = mavlink_msg_sim_state_get_std_dev_vert(msg);
705 sim_state->vn = mavlink_msg_sim_state_get_vn(msg);
706 sim_state->ve = mavlink_msg_sim_state_get_ve(msg);
707 sim_state->vd = mavlink_msg_sim_state_get_vd(msg);
708#else
709 uint8_t len = msg->len < MAVLINK_MSG_ID_SIM_STATE_LEN? msg->len : MAVLINK_MSG_ID_SIM_STATE_LEN;
710 memset(sim_state, 0, MAVLINK_MSG_ID_SIM_STATE_LEN);
711 memcpy(sim_state, _MAV_PAYLOAD(msg), len);
712#endif
713}