2 // MESSAGE SIM_STATE PACKING
4 #define MAVLINK_MSG_ID_SIM_STATE 108
7 typedef 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
; /*< [m/s/s] X acceleration*/
16 float yacc
; /*< [m/s/s] Y acceleration*/
17 float zacc
; /*< [m/s/s] Z acceleration*/
18 float xgyro
; /*< [rad/s] Angular speed around X axis*/
19 float ygyro
; /*< [rad/s] Angular speed around Y axis*/
20 float zgyro
; /*< [rad/s] Angular speed around Z axis*/
21 float lat
; /*< [deg] Latitude*/
22 float lon
; /*< [deg] Longitude*/
23 float alt
; /*< [m] Altitude*/
24 float std_dev_horz
; /*< Horizontal position standard deviation*/
25 float std_dev_vert
; /*< Vertical position standard deviation*/
26 float vn
; /*< [m/s] True velocity in north direction in earth-fixed NED frame*/
27 float ve
; /*< [m/s] True velocity in east direction in earth-fixed NED frame*/
28 float vd
; /*< [m/s] True velocity in down direction in earth-fixed NED frame*/
29 } mavlink_sim_state_t
;
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
36 #define MAVLINK_MSG_ID_SIM_STATE_CRC 32
37 #define MAVLINK_MSG_ID_108_CRC 32
41 #if MAVLINK_COMMAND_24BIT
42 #define MAVLINK_MESSAGE_INFO_SIM_STATE { \
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) }, \
70 #define MAVLINK_MESSAGE_INFO_SIM_STATE { \
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) }, \
99 * @brief Pack a sim_state message
100 * @param system_id ID of this system
101 * @param component_id ID of this component (e.g. 200 for IMU)
102 * @param msg The MAVLink message to compress the data into
104 * @param q1 True attitude quaternion component 1, w (1 in null-rotation)
105 * @param q2 True attitude quaternion component 2, x (0 in null-rotation)
106 * @param q3 True attitude quaternion component 3, y (0 in null-rotation)
107 * @param q4 True attitude quaternion component 4, z (0 in null-rotation)
108 * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs
109 * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs
110 * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs
111 * @param xacc [m/s/s] X acceleration
112 * @param yacc [m/s/s] Y acceleration
113 * @param zacc [m/s/s] Z acceleration
114 * @param xgyro [rad/s] Angular speed around X axis
115 * @param ygyro [rad/s] Angular speed around Y axis
116 * @param zgyro [rad/s] Angular speed around Z axis
117 * @param lat [deg] Latitude
118 * @param lon [deg] Longitude
119 * @param alt [m] Altitude
120 * @param std_dev_horz Horizontal position standard deviation
121 * @param std_dev_vert Vertical position standard deviation
122 * @param vn [m/s] True velocity in north direction in earth-fixed NED frame
123 * @param ve [m/s] True velocity in east direction in earth-fixed NED frame
124 * @param vd [m/s] True velocity in down direction in earth-fixed NED frame
125 * @return length of the message in bytes (excluding serial stream start sign)
127 static 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
)
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
);
154 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_SIM_STATE_LEN
);
156 mavlink_sim_state_t packet
;
162 packet
.pitch
= pitch
;
167 packet
.xgyro
= xgyro
;
168 packet
.ygyro
= ygyro
;
169 packet
.zgyro
= zgyro
;
173 packet
.std_dev_horz
= std_dev_horz
;
174 packet
.std_dev_vert
= std_dev_vert
;
179 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_SIM_STATE_LEN
);
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
);
187 * @brief Pack a sim_state message on a channel
188 * @param system_id ID of this system
189 * @param component_id ID of this component (e.g. 200 for IMU)
190 * @param chan The MAVLink channel this message will be sent over
191 * @param msg The MAVLink message to compress the data into
192 * @param q1 True attitude quaternion component 1, w (1 in null-rotation)
193 * @param q2 True attitude quaternion component 2, x (0 in null-rotation)
194 * @param q3 True attitude quaternion component 3, y (0 in null-rotation)
195 * @param q4 True attitude quaternion component 4, z (0 in null-rotation)
196 * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs
197 * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs
198 * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs
199 * @param xacc [m/s/s] X acceleration
200 * @param yacc [m/s/s] Y acceleration
201 * @param zacc [m/s/s] Z acceleration
202 * @param xgyro [rad/s] Angular speed around X axis
203 * @param ygyro [rad/s] Angular speed around Y axis
204 * @param zgyro [rad/s] Angular speed around Z axis
205 * @param lat [deg] Latitude
206 * @param lon [deg] Longitude
207 * @param alt [m] Altitude
208 * @param std_dev_horz Horizontal position standard deviation
209 * @param std_dev_vert Vertical position standard deviation
210 * @param vn [m/s] True velocity in north direction in earth-fixed NED frame
211 * @param ve [m/s] True velocity in east direction in earth-fixed NED frame
212 * @param vd [m/s] True velocity in down direction in earth-fixed NED frame
213 * @return length of the message in bytes (excluding serial stream start sign)
215 static 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
)
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
);
243 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_SIM_STATE_LEN
);
245 mavlink_sim_state_t packet
;
251 packet
.pitch
= pitch
;
256 packet
.xgyro
= xgyro
;
257 packet
.ygyro
= ygyro
;
258 packet
.zgyro
= zgyro
;
262 packet
.std_dev_horz
= std_dev_horz
;
263 packet
.std_dev_vert
= std_dev_vert
;
268 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_SIM_STATE_LEN
);
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
);
276 * @brief Encode a sim_state struct
278 * @param system_id ID of this system
279 * @param component_id ID of this component (e.g. 200 for IMU)
280 * @param msg The MAVLink message to compress the data into
281 * @param sim_state C-struct to read the message contents from
283 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
)
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
);
289 * @brief Encode a sim_state struct on a channel
291 * @param system_id ID of this system
292 * @param component_id ID of this component (e.g. 200 for IMU)
293 * @param chan The MAVLink channel this message will be sent over
294 * @param msg The MAVLink message to compress the data into
295 * @param sim_state C-struct to read the message contents from
297 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
)
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
);
303 * @brief Send a sim_state message
304 * @param chan MAVLink channel to send the message
306 * @param q1 True attitude quaternion component 1, w (1 in null-rotation)
307 * @param q2 True attitude quaternion component 2, x (0 in null-rotation)
308 * @param q3 True attitude quaternion component 3, y (0 in null-rotation)
309 * @param q4 True attitude quaternion component 4, z (0 in null-rotation)
310 * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs
311 * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs
312 * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs
313 * @param xacc [m/s/s] X acceleration
314 * @param yacc [m/s/s] Y acceleration
315 * @param zacc [m/s/s] Z acceleration
316 * @param xgyro [rad/s] Angular speed around X axis
317 * @param ygyro [rad/s] Angular speed around Y axis
318 * @param zgyro [rad/s] Angular speed around Z axis
319 * @param lat [deg] Latitude
320 * @param lon [deg] Longitude
321 * @param alt [m] Altitude
322 * @param std_dev_horz Horizontal position standard deviation
323 * @param std_dev_vert Vertical position standard deviation
324 * @param vn [m/s] True velocity in north direction in earth-fixed NED frame
325 * @param ve [m/s] True velocity in east direction in earth-fixed NED frame
326 * @param vd [m/s] True velocity in down direction in earth-fixed NED frame
328 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
330 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
)
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
);
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
);
358 mavlink_sim_state_t packet
;
364 packet
.pitch
= pitch
;
369 packet
.xgyro
= xgyro
;
370 packet
.ygyro
= ygyro
;
371 packet
.zgyro
= zgyro
;
375 packet
.std_dev_horz
= std_dev_horz
;
376 packet
.std_dev_vert
= std_dev_vert
;
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
);
386 * @brief Send a sim_state message
387 * @param chan MAVLink channel to send the message
388 * @param struct The MAVLink struct to serialize
390 static inline void mavlink_msg_sim_state_send_struct(mavlink_channel_t chan
, const mavlink_sim_state_t
* sim_state
)
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
);
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
);
399 #if MAVLINK_MSG_ID_SIM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
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.
407 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
)
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
);
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
);
435 mavlink_sim_state_t
*packet
= (mavlink_sim_state_t
*)msgbuf
;
441 packet
->pitch
= pitch
;
446 packet
->xgyro
= xgyro
;
447 packet
->ygyro
= ygyro
;
448 packet
->zgyro
= zgyro
;
452 packet
->std_dev_horz
= std_dev_horz
;
453 packet
->std_dev_vert
= std_dev_vert
;
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
);
465 // MESSAGE SIM_STATE UNPACKING
469 * @brief Get field q1 from sim_state message
471 * @return True attitude quaternion component 1, w (1 in null-rotation)
473 static inline float mavlink_msg_sim_state_get_q1(const mavlink_message_t
* msg
)
475 return _MAV_RETURN_float(msg
, 0);
479 * @brief Get field q2 from sim_state message
481 * @return True attitude quaternion component 2, x (0 in null-rotation)
483 static inline float mavlink_msg_sim_state_get_q2(const mavlink_message_t
* msg
)
485 return _MAV_RETURN_float(msg
, 4);
489 * @brief Get field q3 from sim_state message
491 * @return True attitude quaternion component 3, y (0 in null-rotation)
493 static inline float mavlink_msg_sim_state_get_q3(const mavlink_message_t
* msg
)
495 return _MAV_RETURN_float(msg
, 8);
499 * @brief Get field q4 from sim_state message
501 * @return True attitude quaternion component 4, z (0 in null-rotation)
503 static inline float mavlink_msg_sim_state_get_q4(const mavlink_message_t
* msg
)
505 return _MAV_RETURN_float(msg
, 12);
509 * @brief Get field roll from sim_state message
511 * @return Attitude roll expressed as Euler angles, not recommended except for human-readable outputs
513 static inline float mavlink_msg_sim_state_get_roll(const mavlink_message_t
* msg
)
515 return _MAV_RETURN_float(msg
, 16);
519 * @brief Get field pitch from sim_state message
521 * @return Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs
523 static inline float mavlink_msg_sim_state_get_pitch(const mavlink_message_t
* msg
)
525 return _MAV_RETURN_float(msg
, 20);
529 * @brief Get field yaw from sim_state message
531 * @return Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs
533 static inline float mavlink_msg_sim_state_get_yaw(const mavlink_message_t
* msg
)
535 return _MAV_RETURN_float(msg
, 24);
539 * @brief Get field xacc from sim_state message
541 * @return [m/s/s] X acceleration
543 static inline float mavlink_msg_sim_state_get_xacc(const mavlink_message_t
* msg
)
545 return _MAV_RETURN_float(msg
, 28);
549 * @brief Get field yacc from sim_state message
551 * @return [m/s/s] Y acceleration
553 static inline float mavlink_msg_sim_state_get_yacc(const mavlink_message_t
* msg
)
555 return _MAV_RETURN_float(msg
, 32);
559 * @brief Get field zacc from sim_state message
561 * @return [m/s/s] Z acceleration
563 static inline float mavlink_msg_sim_state_get_zacc(const mavlink_message_t
* msg
)
565 return _MAV_RETURN_float(msg
, 36);
569 * @brief Get field xgyro from sim_state message
571 * @return [rad/s] Angular speed around X axis
573 static inline float mavlink_msg_sim_state_get_xgyro(const mavlink_message_t
* msg
)
575 return _MAV_RETURN_float(msg
, 40);
579 * @brief Get field ygyro from sim_state message
581 * @return [rad/s] Angular speed around Y axis
583 static inline float mavlink_msg_sim_state_get_ygyro(const mavlink_message_t
* msg
)
585 return _MAV_RETURN_float(msg
, 44);
589 * @brief Get field zgyro from sim_state message
591 * @return [rad/s] Angular speed around Z axis
593 static inline float mavlink_msg_sim_state_get_zgyro(const mavlink_message_t
* msg
)
595 return _MAV_RETURN_float(msg
, 48);
599 * @brief Get field lat from sim_state message
601 * @return [deg] Latitude
603 static inline float mavlink_msg_sim_state_get_lat(const mavlink_message_t
* msg
)
605 return _MAV_RETURN_float(msg
, 52);
609 * @brief Get field lon from sim_state message
611 * @return [deg] Longitude
613 static inline float mavlink_msg_sim_state_get_lon(const mavlink_message_t
* msg
)
615 return _MAV_RETURN_float(msg
, 56);
619 * @brief Get field alt from sim_state message
621 * @return [m] Altitude
623 static inline float mavlink_msg_sim_state_get_alt(const mavlink_message_t
* msg
)
625 return _MAV_RETURN_float(msg
, 60);
629 * @brief Get field std_dev_horz from sim_state message
631 * @return Horizontal position standard deviation
633 static inline float mavlink_msg_sim_state_get_std_dev_horz(const mavlink_message_t
* msg
)
635 return _MAV_RETURN_float(msg
, 64);
639 * @brief Get field std_dev_vert from sim_state message
641 * @return Vertical position standard deviation
643 static inline float mavlink_msg_sim_state_get_std_dev_vert(const mavlink_message_t
* msg
)
645 return _MAV_RETURN_float(msg
, 68);
649 * @brief Get field vn from sim_state message
651 * @return [m/s] True velocity in north direction in earth-fixed NED frame
653 static inline float mavlink_msg_sim_state_get_vn(const mavlink_message_t
* msg
)
655 return _MAV_RETURN_float(msg
, 72);
659 * @brief Get field ve from sim_state message
661 * @return [m/s] True velocity in east direction in earth-fixed NED frame
663 static inline float mavlink_msg_sim_state_get_ve(const mavlink_message_t
* msg
)
665 return _MAV_RETURN_float(msg
, 76);
669 * @brief Get field vd from sim_state message
671 * @return [m/s] True velocity in down direction in earth-fixed NED frame
673 static inline float mavlink_msg_sim_state_get_vd(const mavlink_message_t
* msg
)
675 return _MAV_RETURN_float(msg
, 80);
679 * @brief Decode a sim_state message into a struct
681 * @param msg The message to decode
682 * @param sim_state C-struct to decode the message contents into
684 static inline void mavlink_msg_sim_state_decode(const mavlink_message_t
* msg
, mavlink_sim_state_t
* sim_state
)
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
);
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
);