2 // MESSAGE HIL_CONTROLS PACKING
4 #define MAVLINK_MSG_ID_HIL_CONTROLS 91
7 typedef struct __mavlink_hil_controls_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_ailerons
; /*< Control output -1 .. 1*/
10 float pitch_elevator
; /*< Control output -1 .. 1*/
11 float yaw_rudder
; /*< Control output -1 .. 1*/
12 float throttle
; /*< Throttle 0 .. 1*/
13 float aux1
; /*< Aux 1, -1 .. 1*/
14 float aux2
; /*< Aux 2, -1 .. 1*/
15 float aux3
; /*< Aux 3, -1 .. 1*/
16 float aux4
; /*< Aux 4, -1 .. 1*/
17 uint8_t mode
; /*< System mode.*/
18 uint8_t nav_mode
; /*< Navigation mode (MAV_NAV_MODE)*/
19 } mavlink_hil_controls_t
;
21 #define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42
22 #define MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN 42
23 #define MAVLINK_MSG_ID_91_LEN 42
24 #define MAVLINK_MSG_ID_91_MIN_LEN 42
26 #define MAVLINK_MSG_ID_HIL_CONTROLS_CRC 63
27 #define MAVLINK_MSG_ID_91_CRC 63
31 #if MAVLINK_COMMAND_24BIT
32 #define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \
36 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \
37 { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \
38 { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \
39 { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \
40 { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \
41 { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \
42 { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \
43 { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \
44 { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \
45 { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \
46 { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \
50 #define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \
53 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \
54 { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \
55 { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \
56 { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \
57 { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \
58 { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \
59 { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \
60 { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \
61 { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \
62 { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \
63 { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \
69 * @brief Pack a hil_controls message
70 * @param system_id ID of this system
71 * @param component_id ID of this component (e.g. 200 for IMU)
72 * @param msg The MAVLink message to compress the data into
74 * @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.
75 * @param roll_ailerons Control output -1 .. 1
76 * @param pitch_elevator Control output -1 .. 1
77 * @param yaw_rudder Control output -1 .. 1
78 * @param throttle Throttle 0 .. 1
79 * @param aux1 Aux 1, -1 .. 1
80 * @param aux2 Aux 2, -1 .. 1
81 * @param aux3 Aux 3, -1 .. 1
82 * @param aux4 Aux 4, -1 .. 1
83 * @param mode System mode.
84 * @param nav_mode Navigation mode (MAV_NAV_MODE)
85 * @return length of the message in bytes (excluding serial stream start sign)
87 static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
88 uint64_t time_usec
, float roll_ailerons
, float pitch_elevator
, float yaw_rudder
, float throttle
, float aux1
, float aux2
, float aux3
, float aux4
, uint8_t mode
, uint8_t nav_mode
)
90 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
91 char buf
[MAVLINK_MSG_ID_HIL_CONTROLS_LEN
];
92 _mav_put_uint64_t(buf
, 0, time_usec
);
93 _mav_put_float(buf
, 8, roll_ailerons
);
94 _mav_put_float(buf
, 12, pitch_elevator
);
95 _mav_put_float(buf
, 16, yaw_rudder
);
96 _mav_put_float(buf
, 20, throttle
);
97 _mav_put_float(buf
, 24, aux1
);
98 _mav_put_float(buf
, 28, aux2
);
99 _mav_put_float(buf
, 32, aux3
);
100 _mav_put_float(buf
, 36, aux4
);
101 _mav_put_uint8_t(buf
, 40, mode
);
102 _mav_put_uint8_t(buf
, 41, nav_mode
);
104 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_HIL_CONTROLS_LEN
);
106 mavlink_hil_controls_t packet
;
107 packet
.time_usec
= time_usec
;
108 packet
.roll_ailerons
= roll_ailerons
;
109 packet
.pitch_elevator
= pitch_elevator
;
110 packet
.yaw_rudder
= yaw_rudder
;
111 packet
.throttle
= throttle
;
117 packet
.nav_mode
= nav_mode
;
119 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_HIL_CONTROLS_LEN
);
122 msg
->msgid
= MAVLINK_MSG_ID_HIL_CONTROLS
;
123 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN
, MAVLINK_MSG_ID_HIL_CONTROLS_LEN
, MAVLINK_MSG_ID_HIL_CONTROLS_CRC
);
127 * @brief Pack a hil_controls message on a channel
128 * @param system_id ID of this system
129 * @param component_id ID of this component (e.g. 200 for IMU)
130 * @param chan The MAVLink channel this message will be sent over
131 * @param msg The MAVLink message to compress the data into
132 * @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.
133 * @param roll_ailerons Control output -1 .. 1
134 * @param pitch_elevator Control output -1 .. 1
135 * @param yaw_rudder Control output -1 .. 1
136 * @param throttle Throttle 0 .. 1
137 * @param aux1 Aux 1, -1 .. 1
138 * @param aux2 Aux 2, -1 .. 1
139 * @param aux3 Aux 3, -1 .. 1
140 * @param aux4 Aux 4, -1 .. 1
141 * @param mode System mode.
142 * @param nav_mode Navigation mode (MAV_NAV_MODE)
143 * @return length of the message in bytes (excluding serial stream start sign)
145 static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
146 mavlink_message_t
* msg
,
147 uint64_t time_usec
,float roll_ailerons
,float pitch_elevator
,float yaw_rudder
,float throttle
,float aux1
,float aux2
,float aux3
,float aux4
,uint8_t mode
,uint8_t nav_mode
)
149 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
150 char buf
[MAVLINK_MSG_ID_HIL_CONTROLS_LEN
];
151 _mav_put_uint64_t(buf
, 0, time_usec
);
152 _mav_put_float(buf
, 8, roll_ailerons
);
153 _mav_put_float(buf
, 12, pitch_elevator
);
154 _mav_put_float(buf
, 16, yaw_rudder
);
155 _mav_put_float(buf
, 20, throttle
);
156 _mav_put_float(buf
, 24, aux1
);
157 _mav_put_float(buf
, 28, aux2
);
158 _mav_put_float(buf
, 32, aux3
);
159 _mav_put_float(buf
, 36, aux4
);
160 _mav_put_uint8_t(buf
, 40, mode
);
161 _mav_put_uint8_t(buf
, 41, nav_mode
);
163 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_HIL_CONTROLS_LEN
);
165 mavlink_hil_controls_t packet
;
166 packet
.time_usec
= time_usec
;
167 packet
.roll_ailerons
= roll_ailerons
;
168 packet
.pitch_elevator
= pitch_elevator
;
169 packet
.yaw_rudder
= yaw_rudder
;
170 packet
.throttle
= throttle
;
176 packet
.nav_mode
= nav_mode
;
178 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_HIL_CONTROLS_LEN
);
181 msg
->msgid
= MAVLINK_MSG_ID_HIL_CONTROLS
;
182 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN
, MAVLINK_MSG_ID_HIL_CONTROLS_LEN
, MAVLINK_MSG_ID_HIL_CONTROLS_CRC
);
186 * @brief Encode a hil_controls struct
188 * @param system_id ID of this system
189 * @param component_id ID of this component (e.g. 200 for IMU)
190 * @param msg The MAVLink message to compress the data into
191 * @param hil_controls C-struct to read the message contents from
193 static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_hil_controls_t
* hil_controls
)
195 return mavlink_msg_hil_controls_pack(system_id
, component_id
, msg
, hil_controls
->time_usec
, hil_controls
->roll_ailerons
, hil_controls
->pitch_elevator
, hil_controls
->yaw_rudder
, hil_controls
->throttle
, hil_controls
->aux1
, hil_controls
->aux2
, hil_controls
->aux3
, hil_controls
->aux4
, hil_controls
->mode
, hil_controls
->nav_mode
);
199 * @brief Encode a hil_controls struct on a channel
201 * @param system_id ID of this system
202 * @param component_id ID of this component (e.g. 200 for IMU)
203 * @param chan The MAVLink channel this message will be sent over
204 * @param msg The MAVLink message to compress the data into
205 * @param hil_controls C-struct to read the message contents from
207 static inline uint16_t mavlink_msg_hil_controls_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_hil_controls_t
* hil_controls
)
209 return mavlink_msg_hil_controls_pack_chan(system_id
, component_id
, chan
, msg
, hil_controls
->time_usec
, hil_controls
->roll_ailerons
, hil_controls
->pitch_elevator
, hil_controls
->yaw_rudder
, hil_controls
->throttle
, hil_controls
->aux1
, hil_controls
->aux2
, hil_controls
->aux3
, hil_controls
->aux4
, hil_controls
->mode
, hil_controls
->nav_mode
);
213 * @brief Send a hil_controls message
214 * @param chan MAVLink channel to send the message
216 * @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.
217 * @param roll_ailerons Control output -1 .. 1
218 * @param pitch_elevator Control output -1 .. 1
219 * @param yaw_rudder Control output -1 .. 1
220 * @param throttle Throttle 0 .. 1
221 * @param aux1 Aux 1, -1 .. 1
222 * @param aux2 Aux 2, -1 .. 1
223 * @param aux3 Aux 3, -1 .. 1
224 * @param aux4 Aux 4, -1 .. 1
225 * @param mode System mode.
226 * @param nav_mode Navigation mode (MAV_NAV_MODE)
228 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
230 static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan
, uint64_t time_usec
, float roll_ailerons
, float pitch_elevator
, float yaw_rudder
, float throttle
, float aux1
, float aux2
, float aux3
, float aux4
, uint8_t mode
, uint8_t nav_mode
)
232 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
233 char buf
[MAVLINK_MSG_ID_HIL_CONTROLS_LEN
];
234 _mav_put_uint64_t(buf
, 0, time_usec
);
235 _mav_put_float(buf
, 8, roll_ailerons
);
236 _mav_put_float(buf
, 12, pitch_elevator
);
237 _mav_put_float(buf
, 16, yaw_rudder
);
238 _mav_put_float(buf
, 20, throttle
);
239 _mav_put_float(buf
, 24, aux1
);
240 _mav_put_float(buf
, 28, aux2
);
241 _mav_put_float(buf
, 32, aux3
);
242 _mav_put_float(buf
, 36, aux4
);
243 _mav_put_uint8_t(buf
, 40, mode
);
244 _mav_put_uint8_t(buf
, 41, nav_mode
);
246 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_CONTROLS
, buf
, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN
, MAVLINK_MSG_ID_HIL_CONTROLS_LEN
, MAVLINK_MSG_ID_HIL_CONTROLS_CRC
);
248 mavlink_hil_controls_t packet
;
249 packet
.time_usec
= time_usec
;
250 packet
.roll_ailerons
= roll_ailerons
;
251 packet
.pitch_elevator
= pitch_elevator
;
252 packet
.yaw_rudder
= yaw_rudder
;
253 packet
.throttle
= throttle
;
259 packet
.nav_mode
= nav_mode
;
261 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_CONTROLS
, (const char *)&packet
, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN
, MAVLINK_MSG_ID_HIL_CONTROLS_LEN
, MAVLINK_MSG_ID_HIL_CONTROLS_CRC
);
266 * @brief Send a hil_controls message
267 * @param chan MAVLink channel to send the message
268 * @param struct The MAVLink struct to serialize
270 static inline void mavlink_msg_hil_controls_send_struct(mavlink_channel_t chan
, const mavlink_hil_controls_t
* hil_controls
)
272 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
273 mavlink_msg_hil_controls_send(chan
, hil_controls
->time_usec
, hil_controls
->roll_ailerons
, hil_controls
->pitch_elevator
, hil_controls
->yaw_rudder
, hil_controls
->throttle
, hil_controls
->aux1
, hil_controls
->aux2
, hil_controls
->aux3
, hil_controls
->aux4
, hil_controls
->mode
, hil_controls
->nav_mode
);
275 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_CONTROLS
, (const char *)hil_controls
, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN
, MAVLINK_MSG_ID_HIL_CONTROLS_LEN
, MAVLINK_MSG_ID_HIL_CONTROLS_CRC
);
279 #if MAVLINK_MSG_ID_HIL_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
281 This varient of _send() can be used to save stack space by re-using
282 memory from the receive buffer. The caller provides a
283 mavlink_message_t which is the size of a full mavlink message. This
284 is usually the receive buffer for the channel, and allows a reply to an
285 incoming message with minimum stack space usage.
287 static inline void mavlink_msg_hil_controls_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint64_t time_usec
, float roll_ailerons
, float pitch_elevator
, float yaw_rudder
, float throttle
, float aux1
, float aux2
, float aux3
, float aux4
, uint8_t mode
, uint8_t nav_mode
)
289 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
290 char *buf
= (char *)msgbuf
;
291 _mav_put_uint64_t(buf
, 0, time_usec
);
292 _mav_put_float(buf
, 8, roll_ailerons
);
293 _mav_put_float(buf
, 12, pitch_elevator
);
294 _mav_put_float(buf
, 16, yaw_rudder
);
295 _mav_put_float(buf
, 20, throttle
);
296 _mav_put_float(buf
, 24, aux1
);
297 _mav_put_float(buf
, 28, aux2
);
298 _mav_put_float(buf
, 32, aux3
);
299 _mav_put_float(buf
, 36, aux4
);
300 _mav_put_uint8_t(buf
, 40, mode
);
301 _mav_put_uint8_t(buf
, 41, nav_mode
);
303 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_CONTROLS
, buf
, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN
, MAVLINK_MSG_ID_HIL_CONTROLS_LEN
, MAVLINK_MSG_ID_HIL_CONTROLS_CRC
);
305 mavlink_hil_controls_t
*packet
= (mavlink_hil_controls_t
*)msgbuf
;
306 packet
->time_usec
= time_usec
;
307 packet
->roll_ailerons
= roll_ailerons
;
308 packet
->pitch_elevator
= pitch_elevator
;
309 packet
->yaw_rudder
= yaw_rudder
;
310 packet
->throttle
= throttle
;
316 packet
->nav_mode
= nav_mode
;
318 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_CONTROLS
, (const char *)packet
, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN
, MAVLINK_MSG_ID_HIL_CONTROLS_LEN
, MAVLINK_MSG_ID_HIL_CONTROLS_CRC
);
325 // MESSAGE HIL_CONTROLS UNPACKING
329 * @brief Get field time_usec from hil_controls message
331 * @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.
333 static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t
* msg
)
335 return _MAV_RETURN_uint64_t(msg
, 0);
339 * @brief Get field roll_ailerons from hil_controls message
341 * @return Control output -1 .. 1
343 static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t
* msg
)
345 return _MAV_RETURN_float(msg
, 8);
349 * @brief Get field pitch_elevator from hil_controls message
351 * @return Control output -1 .. 1
353 static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t
* msg
)
355 return _MAV_RETURN_float(msg
, 12);
359 * @brief Get field yaw_rudder from hil_controls message
361 * @return Control output -1 .. 1
363 static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t
* msg
)
365 return _MAV_RETURN_float(msg
, 16);
369 * @brief Get field throttle from hil_controls message
371 * @return Throttle 0 .. 1
373 static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t
* msg
)
375 return _MAV_RETURN_float(msg
, 20);
379 * @brief Get field aux1 from hil_controls message
381 * @return Aux 1, -1 .. 1
383 static inline float mavlink_msg_hil_controls_get_aux1(const mavlink_message_t
* msg
)
385 return _MAV_RETURN_float(msg
, 24);
389 * @brief Get field aux2 from hil_controls message
391 * @return Aux 2, -1 .. 1
393 static inline float mavlink_msg_hil_controls_get_aux2(const mavlink_message_t
* msg
)
395 return _MAV_RETURN_float(msg
, 28);
399 * @brief Get field aux3 from hil_controls message
401 * @return Aux 3, -1 .. 1
403 static inline float mavlink_msg_hil_controls_get_aux3(const mavlink_message_t
* msg
)
405 return _MAV_RETURN_float(msg
, 32);
409 * @brief Get field aux4 from hil_controls message
411 * @return Aux 4, -1 .. 1
413 static inline float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t
* msg
)
415 return _MAV_RETURN_float(msg
, 36);
419 * @brief Get field mode from hil_controls message
421 * @return System mode.
423 static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t
* msg
)
425 return _MAV_RETURN_uint8_t(msg
, 40);
429 * @brief Get field nav_mode from hil_controls message
431 * @return Navigation mode (MAV_NAV_MODE)
433 static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t
* msg
)
435 return _MAV_RETURN_uint8_t(msg
, 41);
439 * @brief Decode a hil_controls message into a struct
441 * @param msg The message to decode
442 * @param hil_controls C-struct to decode the message contents into
444 static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t
* msg
, mavlink_hil_controls_t
* hil_controls
)
446 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
447 hil_controls
->time_usec
= mavlink_msg_hil_controls_get_time_usec(msg
);
448 hil_controls
->roll_ailerons
= mavlink_msg_hil_controls_get_roll_ailerons(msg
);
449 hil_controls
->pitch_elevator
= mavlink_msg_hil_controls_get_pitch_elevator(msg
);
450 hil_controls
->yaw_rudder
= mavlink_msg_hil_controls_get_yaw_rudder(msg
);
451 hil_controls
->throttle
= mavlink_msg_hil_controls_get_throttle(msg
);
452 hil_controls
->aux1
= mavlink_msg_hil_controls_get_aux1(msg
);
453 hil_controls
->aux2
= mavlink_msg_hil_controls_get_aux2(msg
);
454 hil_controls
->aux3
= mavlink_msg_hil_controls_get_aux3(msg
);
455 hil_controls
->aux4
= mavlink_msg_hil_controls_get_aux4(msg
);
456 hil_controls
->mode
= mavlink_msg_hil_controls_get_mode(msg
);
457 hil_controls
->nav_mode
= mavlink_msg_hil_controls_get_nav_mode(msg
);
459 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_HIL_CONTROLS_LEN
? msg
->len
: MAVLINK_MSG_ID_HIL_CONTROLS_LEN
;
460 memset(hil_controls
, 0, MAVLINK_MSG_ID_HIL_CONTROLS_LEN
);
461 memcpy(hil_controls
, _MAV_PAYLOAD(msg
), len
);