2 // MESSAGE HIL_STATE PACKING
4 #define MAVLINK_MSG_ID_HIL_STATE 90
7 typedef struct __mavlink_hil_state_t
{
8 uint64_t time_usec
; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
9 float roll
; /*< [rad] Roll angle*/
10 float pitch
; /*< [rad] Pitch angle*/
11 float yaw
; /*< [rad] Yaw angle*/
12 float rollspeed
; /*< [rad/s] Body frame roll / phi angular speed*/
13 float pitchspeed
; /*< [rad/s] Body frame pitch / theta angular speed*/
14 float yawspeed
; /*< [rad/s] Body frame yaw / psi angular speed*/
15 int32_t lat
; /*< [degE7] Latitude*/
16 int32_t lon
; /*< [degE7] Longitude*/
17 int32_t alt
; /*< [mm] Altitude*/
18 int16_t vx
; /*< [cm/s] Ground X Speed (Latitude)*/
19 int16_t vy
; /*< [cm/s] Ground Y Speed (Longitude)*/
20 int16_t vz
; /*< [cm/s] Ground Z Speed (Altitude)*/
21 int16_t xacc
; /*< [mG] X acceleration*/
22 int16_t yacc
; /*< [mG] Y acceleration*/
23 int16_t zacc
; /*< [mG] Z acceleration*/
24 } mavlink_hil_state_t
;
26 #define MAVLINK_MSG_ID_HIL_STATE_LEN 56
27 #define MAVLINK_MSG_ID_HIL_STATE_MIN_LEN 56
28 #define MAVLINK_MSG_ID_90_LEN 56
29 #define MAVLINK_MSG_ID_90_MIN_LEN 56
31 #define MAVLINK_MSG_ID_HIL_STATE_CRC 183
32 #define MAVLINK_MSG_ID_90_CRC 183
36 #if MAVLINK_COMMAND_24BIT
37 #define MAVLINK_MESSAGE_INFO_HIL_STATE { \
41 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \
42 { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \
43 { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \
44 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \
45 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \
46 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \
47 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \
48 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \
49 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \
50 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \
51 { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \
52 { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \
53 { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \
54 { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \
55 { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \
56 { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \
60 #define MAVLINK_MESSAGE_INFO_HIL_STATE { \
63 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \
64 { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \
65 { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \
66 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \
67 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \
68 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \
69 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \
70 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \
71 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \
72 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \
73 { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \
74 { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \
75 { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \
76 { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \
77 { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \
78 { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \
84 * @brief Pack a hil_state message
85 * @param system_id ID of this system
86 * @param component_id ID of this component (e.g. 200 for IMU)
87 * @param msg The MAVLink message to compress the data into
89 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
90 * @param roll [rad] Roll angle
91 * @param pitch [rad] Pitch angle
92 * @param yaw [rad] Yaw angle
93 * @param rollspeed [rad/s] Body frame roll / phi angular speed
94 * @param pitchspeed [rad/s] Body frame pitch / theta angular speed
95 * @param yawspeed [rad/s] Body frame yaw / psi angular speed
96 * @param lat [degE7] Latitude
97 * @param lon [degE7] Longitude
98 * @param alt [mm] Altitude
99 * @param vx [cm/s] Ground X Speed (Latitude)
100 * @param vy [cm/s] Ground Y Speed (Longitude)
101 * @param vz [cm/s] Ground Z Speed (Altitude)
102 * @param xacc [mG] X acceleration
103 * @param yacc [mG] Y acceleration
104 * @param zacc [mG] Z acceleration
105 * @return length of the message in bytes (excluding serial stream start sign)
107 static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
108 uint64_t time_usec
, float roll
, float pitch
, float yaw
, float rollspeed
, float pitchspeed
, float yawspeed
, int32_t lat
, int32_t lon
, int32_t alt
, int16_t vx
, int16_t vy
, int16_t vz
, int16_t xacc
, int16_t yacc
, int16_t zacc
)
110 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
111 char buf
[MAVLINK_MSG_ID_HIL_STATE_LEN
];
112 _mav_put_uint64_t(buf
, 0, time_usec
);
113 _mav_put_float(buf
, 8, roll
);
114 _mav_put_float(buf
, 12, pitch
);
115 _mav_put_float(buf
, 16, yaw
);
116 _mav_put_float(buf
, 20, rollspeed
);
117 _mav_put_float(buf
, 24, pitchspeed
);
118 _mav_put_float(buf
, 28, yawspeed
);
119 _mav_put_int32_t(buf
, 32, lat
);
120 _mav_put_int32_t(buf
, 36, lon
);
121 _mav_put_int32_t(buf
, 40, alt
);
122 _mav_put_int16_t(buf
, 44, vx
);
123 _mav_put_int16_t(buf
, 46, vy
);
124 _mav_put_int16_t(buf
, 48, vz
);
125 _mav_put_int16_t(buf
, 50, xacc
);
126 _mav_put_int16_t(buf
, 52, yacc
);
127 _mav_put_int16_t(buf
, 54, zacc
);
129 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_HIL_STATE_LEN
);
131 mavlink_hil_state_t packet
;
132 packet
.time_usec
= time_usec
;
134 packet
.pitch
= pitch
;
136 packet
.rollspeed
= rollspeed
;
137 packet
.pitchspeed
= pitchspeed
;
138 packet
.yawspeed
= yawspeed
;
149 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_HIL_STATE_LEN
);
152 msg
->msgid
= MAVLINK_MSG_ID_HIL_STATE
;
153 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN
, MAVLINK_MSG_ID_HIL_STATE_LEN
, MAVLINK_MSG_ID_HIL_STATE_CRC
);
157 * @brief Pack a hil_state message on a channel
158 * @param system_id ID of this system
159 * @param component_id ID of this component (e.g. 200 for IMU)
160 * @param chan The MAVLink channel this message will be sent over
161 * @param msg The MAVLink message to compress the data into
162 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
163 * @param roll [rad] Roll angle
164 * @param pitch [rad] Pitch angle
165 * @param yaw [rad] Yaw angle
166 * @param rollspeed [rad/s] Body frame roll / phi angular speed
167 * @param pitchspeed [rad/s] Body frame pitch / theta angular speed
168 * @param yawspeed [rad/s] Body frame yaw / psi angular speed
169 * @param lat [degE7] Latitude
170 * @param lon [degE7] Longitude
171 * @param alt [mm] Altitude
172 * @param vx [cm/s] Ground X Speed (Latitude)
173 * @param vy [cm/s] Ground Y Speed (Longitude)
174 * @param vz [cm/s] Ground Z Speed (Altitude)
175 * @param xacc [mG] X acceleration
176 * @param yacc [mG] Y acceleration
177 * @param zacc [mG] Z acceleration
178 * @return length of the message in bytes (excluding serial stream start sign)
180 static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
181 mavlink_message_t
* msg
,
182 uint64_t time_usec
,float roll
,float pitch
,float yaw
,float rollspeed
,float pitchspeed
,float yawspeed
,int32_t lat
,int32_t lon
,int32_t alt
,int16_t vx
,int16_t vy
,int16_t vz
,int16_t xacc
,int16_t yacc
,int16_t zacc
)
184 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
185 char buf
[MAVLINK_MSG_ID_HIL_STATE_LEN
];
186 _mav_put_uint64_t(buf
, 0, time_usec
);
187 _mav_put_float(buf
, 8, roll
);
188 _mav_put_float(buf
, 12, pitch
);
189 _mav_put_float(buf
, 16, yaw
);
190 _mav_put_float(buf
, 20, rollspeed
);
191 _mav_put_float(buf
, 24, pitchspeed
);
192 _mav_put_float(buf
, 28, yawspeed
);
193 _mav_put_int32_t(buf
, 32, lat
);
194 _mav_put_int32_t(buf
, 36, lon
);
195 _mav_put_int32_t(buf
, 40, alt
);
196 _mav_put_int16_t(buf
, 44, vx
);
197 _mav_put_int16_t(buf
, 46, vy
);
198 _mav_put_int16_t(buf
, 48, vz
);
199 _mav_put_int16_t(buf
, 50, xacc
);
200 _mav_put_int16_t(buf
, 52, yacc
);
201 _mav_put_int16_t(buf
, 54, zacc
);
203 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_HIL_STATE_LEN
);
205 mavlink_hil_state_t packet
;
206 packet
.time_usec
= time_usec
;
208 packet
.pitch
= pitch
;
210 packet
.rollspeed
= rollspeed
;
211 packet
.pitchspeed
= pitchspeed
;
212 packet
.yawspeed
= yawspeed
;
223 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_HIL_STATE_LEN
);
226 msg
->msgid
= MAVLINK_MSG_ID_HIL_STATE
;
227 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN
, MAVLINK_MSG_ID_HIL_STATE_LEN
, MAVLINK_MSG_ID_HIL_STATE_CRC
);
231 * @brief Encode a hil_state struct
233 * @param system_id ID of this system
234 * @param component_id ID of this component (e.g. 200 for IMU)
235 * @param msg The MAVLink message to compress the data into
236 * @param hil_state C-struct to read the message contents from
238 static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_hil_state_t
* hil_state
)
240 return mavlink_msg_hil_state_pack(system_id
, component_id
, msg
, hil_state
->time_usec
, hil_state
->roll
, hil_state
->pitch
, hil_state
->yaw
, hil_state
->rollspeed
, hil_state
->pitchspeed
, hil_state
->yawspeed
, hil_state
->lat
, hil_state
->lon
, hil_state
->alt
, hil_state
->vx
, hil_state
->vy
, hil_state
->vz
, hil_state
->xacc
, hil_state
->yacc
, hil_state
->zacc
);
244 * @brief Encode a hil_state struct on a channel
246 * @param system_id ID of this system
247 * @param component_id ID of this component (e.g. 200 for IMU)
248 * @param chan The MAVLink channel this message will be sent over
249 * @param msg The MAVLink message to compress the data into
250 * @param hil_state C-struct to read the message contents from
252 static inline uint16_t mavlink_msg_hil_state_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_hil_state_t
* hil_state
)
254 return mavlink_msg_hil_state_pack_chan(system_id
, component_id
, chan
, msg
, hil_state
->time_usec
, hil_state
->roll
, hil_state
->pitch
, hil_state
->yaw
, hil_state
->rollspeed
, hil_state
->pitchspeed
, hil_state
->yawspeed
, hil_state
->lat
, hil_state
->lon
, hil_state
->alt
, hil_state
->vx
, hil_state
->vy
, hil_state
->vz
, hil_state
->xacc
, hil_state
->yacc
, hil_state
->zacc
);
258 * @brief Send a hil_state message
259 * @param chan MAVLink channel to send the message
261 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
262 * @param roll [rad] Roll angle
263 * @param pitch [rad] Pitch angle
264 * @param yaw [rad] Yaw angle
265 * @param rollspeed [rad/s] Body frame roll / phi angular speed
266 * @param pitchspeed [rad/s] Body frame pitch / theta angular speed
267 * @param yawspeed [rad/s] Body frame yaw / psi angular speed
268 * @param lat [degE7] Latitude
269 * @param lon [degE7] Longitude
270 * @param alt [mm] Altitude
271 * @param vx [cm/s] Ground X Speed (Latitude)
272 * @param vy [cm/s] Ground Y Speed (Longitude)
273 * @param vz [cm/s] Ground Z Speed (Altitude)
274 * @param xacc [mG] X acceleration
275 * @param yacc [mG] Y acceleration
276 * @param zacc [mG] Z acceleration
278 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
280 static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan
, uint64_t time_usec
, float roll
, float pitch
, float yaw
, float rollspeed
, float pitchspeed
, float yawspeed
, int32_t lat
, int32_t lon
, int32_t alt
, int16_t vx
, int16_t vy
, int16_t vz
, int16_t xacc
, int16_t yacc
, int16_t zacc
)
282 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
283 char buf
[MAVLINK_MSG_ID_HIL_STATE_LEN
];
284 _mav_put_uint64_t(buf
, 0, time_usec
);
285 _mav_put_float(buf
, 8, roll
);
286 _mav_put_float(buf
, 12, pitch
);
287 _mav_put_float(buf
, 16, yaw
);
288 _mav_put_float(buf
, 20, rollspeed
);
289 _mav_put_float(buf
, 24, pitchspeed
);
290 _mav_put_float(buf
, 28, yawspeed
);
291 _mav_put_int32_t(buf
, 32, lat
);
292 _mav_put_int32_t(buf
, 36, lon
);
293 _mav_put_int32_t(buf
, 40, alt
);
294 _mav_put_int16_t(buf
, 44, vx
);
295 _mav_put_int16_t(buf
, 46, vy
);
296 _mav_put_int16_t(buf
, 48, vz
);
297 _mav_put_int16_t(buf
, 50, xacc
);
298 _mav_put_int16_t(buf
, 52, yacc
);
299 _mav_put_int16_t(buf
, 54, zacc
);
301 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_STATE
, buf
, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN
, MAVLINK_MSG_ID_HIL_STATE_LEN
, MAVLINK_MSG_ID_HIL_STATE_CRC
);
303 mavlink_hil_state_t packet
;
304 packet
.time_usec
= time_usec
;
306 packet
.pitch
= pitch
;
308 packet
.rollspeed
= rollspeed
;
309 packet
.pitchspeed
= pitchspeed
;
310 packet
.yawspeed
= yawspeed
;
321 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_STATE
, (const char *)&packet
, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN
, MAVLINK_MSG_ID_HIL_STATE_LEN
, MAVLINK_MSG_ID_HIL_STATE_CRC
);
326 * @brief Send a hil_state message
327 * @param chan MAVLink channel to send the message
328 * @param struct The MAVLink struct to serialize
330 static inline void mavlink_msg_hil_state_send_struct(mavlink_channel_t chan
, const mavlink_hil_state_t
* hil_state
)
332 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
333 mavlink_msg_hil_state_send(chan
, hil_state
->time_usec
, hil_state
->roll
, hil_state
->pitch
, hil_state
->yaw
, hil_state
->rollspeed
, hil_state
->pitchspeed
, hil_state
->yawspeed
, hil_state
->lat
, hil_state
->lon
, hil_state
->alt
, hil_state
->vx
, hil_state
->vy
, hil_state
->vz
, hil_state
->xacc
, hil_state
->yacc
, hil_state
->zacc
);
335 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_STATE
, (const char *)hil_state
, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN
, MAVLINK_MSG_ID_HIL_STATE_LEN
, MAVLINK_MSG_ID_HIL_STATE_CRC
);
339 #if MAVLINK_MSG_ID_HIL_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
341 This varient of _send() can be used to save stack space by re-using
342 memory from the receive buffer. The caller provides a
343 mavlink_message_t which is the size of a full mavlink message. This
344 is usually the receive buffer for the channel, and allows a reply to an
345 incoming message with minimum stack space usage.
347 static inline void mavlink_msg_hil_state_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint64_t time_usec
, float roll
, float pitch
, float yaw
, float rollspeed
, float pitchspeed
, float yawspeed
, int32_t lat
, int32_t lon
, int32_t alt
, int16_t vx
, int16_t vy
, int16_t vz
, int16_t xacc
, int16_t yacc
, int16_t zacc
)
349 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
350 char *buf
= (char *)msgbuf
;
351 _mav_put_uint64_t(buf
, 0, time_usec
);
352 _mav_put_float(buf
, 8, roll
);
353 _mav_put_float(buf
, 12, pitch
);
354 _mav_put_float(buf
, 16, yaw
);
355 _mav_put_float(buf
, 20, rollspeed
);
356 _mav_put_float(buf
, 24, pitchspeed
);
357 _mav_put_float(buf
, 28, yawspeed
);
358 _mav_put_int32_t(buf
, 32, lat
);
359 _mav_put_int32_t(buf
, 36, lon
);
360 _mav_put_int32_t(buf
, 40, alt
);
361 _mav_put_int16_t(buf
, 44, vx
);
362 _mav_put_int16_t(buf
, 46, vy
);
363 _mav_put_int16_t(buf
, 48, vz
);
364 _mav_put_int16_t(buf
, 50, xacc
);
365 _mav_put_int16_t(buf
, 52, yacc
);
366 _mav_put_int16_t(buf
, 54, zacc
);
368 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_STATE
, buf
, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN
, MAVLINK_MSG_ID_HIL_STATE_LEN
, MAVLINK_MSG_ID_HIL_STATE_CRC
);
370 mavlink_hil_state_t
*packet
= (mavlink_hil_state_t
*)msgbuf
;
371 packet
->time_usec
= time_usec
;
373 packet
->pitch
= pitch
;
375 packet
->rollspeed
= rollspeed
;
376 packet
->pitchspeed
= pitchspeed
;
377 packet
->yawspeed
= yawspeed
;
388 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_STATE
, (const char *)packet
, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN
, MAVLINK_MSG_ID_HIL_STATE_LEN
, MAVLINK_MSG_ID_HIL_STATE_CRC
);
395 // MESSAGE HIL_STATE UNPACKING
399 * @brief Get field time_usec from hil_state message
401 * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
403 static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t
* msg
)
405 return _MAV_RETURN_uint64_t(msg
, 0);
409 * @brief Get field roll from hil_state message
411 * @return [rad] Roll angle
413 static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t
* msg
)
415 return _MAV_RETURN_float(msg
, 8);
419 * @brief Get field pitch from hil_state message
421 * @return [rad] Pitch angle
423 static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t
* msg
)
425 return _MAV_RETURN_float(msg
, 12);
429 * @brief Get field yaw from hil_state message
431 * @return [rad] Yaw angle
433 static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t
* msg
)
435 return _MAV_RETURN_float(msg
, 16);
439 * @brief Get field rollspeed from hil_state message
441 * @return [rad/s] Body frame roll / phi angular speed
443 static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t
* msg
)
445 return _MAV_RETURN_float(msg
, 20);
449 * @brief Get field pitchspeed from hil_state message
451 * @return [rad/s] Body frame pitch / theta angular speed
453 static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t
* msg
)
455 return _MAV_RETURN_float(msg
, 24);
459 * @brief Get field yawspeed from hil_state message
461 * @return [rad/s] Body frame yaw / psi angular speed
463 static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t
* msg
)
465 return _MAV_RETURN_float(msg
, 28);
469 * @brief Get field lat from hil_state message
471 * @return [degE7] Latitude
473 static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t
* msg
)
475 return _MAV_RETURN_int32_t(msg
, 32);
479 * @brief Get field lon from hil_state message
481 * @return [degE7] Longitude
483 static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t
* msg
)
485 return _MAV_RETURN_int32_t(msg
, 36);
489 * @brief Get field alt from hil_state message
491 * @return [mm] Altitude
493 static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t
* msg
)
495 return _MAV_RETURN_int32_t(msg
, 40);
499 * @brief Get field vx from hil_state message
501 * @return [cm/s] Ground X Speed (Latitude)
503 static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t
* msg
)
505 return _MAV_RETURN_int16_t(msg
, 44);
509 * @brief Get field vy from hil_state message
511 * @return [cm/s] Ground Y Speed (Longitude)
513 static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t
* msg
)
515 return _MAV_RETURN_int16_t(msg
, 46);
519 * @brief Get field vz from hil_state message
521 * @return [cm/s] Ground Z Speed (Altitude)
523 static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t
* msg
)
525 return _MAV_RETURN_int16_t(msg
, 48);
529 * @brief Get field xacc from hil_state message
531 * @return [mG] X acceleration
533 static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t
* msg
)
535 return _MAV_RETURN_int16_t(msg
, 50);
539 * @brief Get field yacc from hil_state message
541 * @return [mG] Y acceleration
543 static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t
* msg
)
545 return _MAV_RETURN_int16_t(msg
, 52);
549 * @brief Get field zacc from hil_state message
551 * @return [mG] Z acceleration
553 static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t
* msg
)
555 return _MAV_RETURN_int16_t(msg
, 54);
559 * @brief Decode a hil_state message into a struct
561 * @param msg The message to decode
562 * @param hil_state C-struct to decode the message contents into
564 static inline void mavlink_msg_hil_state_decode(const mavlink_message_t
* msg
, mavlink_hil_state_t
* hil_state
)
566 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
567 hil_state
->time_usec
= mavlink_msg_hil_state_get_time_usec(msg
);
568 hil_state
->roll
= mavlink_msg_hil_state_get_roll(msg
);
569 hil_state
->pitch
= mavlink_msg_hil_state_get_pitch(msg
);
570 hil_state
->yaw
= mavlink_msg_hil_state_get_yaw(msg
);
571 hil_state
->rollspeed
= mavlink_msg_hil_state_get_rollspeed(msg
);
572 hil_state
->pitchspeed
= mavlink_msg_hil_state_get_pitchspeed(msg
);
573 hil_state
->yawspeed
= mavlink_msg_hil_state_get_yawspeed(msg
);
574 hil_state
->lat
= mavlink_msg_hil_state_get_lat(msg
);
575 hil_state
->lon
= mavlink_msg_hil_state_get_lon(msg
);
576 hil_state
->alt
= mavlink_msg_hil_state_get_alt(msg
);
577 hil_state
->vx
= mavlink_msg_hil_state_get_vx(msg
);
578 hil_state
->vy
= mavlink_msg_hil_state_get_vy(msg
);
579 hil_state
->vz
= mavlink_msg_hil_state_get_vz(msg
);
580 hil_state
->xacc
= mavlink_msg_hil_state_get_xacc(msg
);
581 hil_state
->yacc
= mavlink_msg_hil_state_get_yacc(msg
);
582 hil_state
->zacc
= mavlink_msg_hil_state_get_zacc(msg
);
584 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_HIL_STATE_LEN
? msg
->len
: MAVLINK_MSG_ID_HIL_STATE_LEN
;
585 memset(hil_state
, 0, MAVLINK_MSG_ID_HIL_STATE_LEN
);
586 memcpy(hil_state
, _MAV_PAYLOAD(msg
), len
);