3 #define MAVLINK_MSG_ID_HIL_CONTROLS 91
20 #define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42
21 #define MAVLINK_MSG_ID_91_LEN 42
23 #define MAVLINK_MSG_ID_HIL_CONTROLS_CRC 63
24 #define MAVLINK_MSG_ID_91_CRC 63
28 #define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \
31 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \
32 { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \
33 { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \
34 { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \
35 { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \
36 { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \
37 { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \
38 { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \
39 { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \
40 { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \
41 { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \
65 static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
66 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)
68 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
69 char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN];
70 _mav_put_uint64_t(buf, 0, time_usec);
71 _mav_put_float(buf, 8, roll_ailerons);
72 _mav_put_float(buf, 12, pitch_elevator);
73 _mav_put_float(buf, 16, yaw_rudder);
74 _mav_put_float(buf, 20, throttle);
75 _mav_put_float(buf, 24, aux1);
76 _mav_put_float(buf, 28, aux2);
77 _mav_put_float(buf, 32, aux3);
78 _mav_put_float(buf, 36, aux4);
79 _mav_put_uint8_t(buf, 40, mode);
80 _mav_put_uint8_t(buf, 41, nav_mode);
82 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
97 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
100 msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
101 #if MAVLINK_CRC_EXTRA
102 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
104 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
127 static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
128 mavlink_message_t* msg,
129 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)
131 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
132 char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN];
133 _mav_put_uint64_t(buf, 0, time_usec);
134 _mav_put_float(buf, 8, roll_ailerons);
135 _mav_put_float(buf, 12, pitch_elevator);
136 _mav_put_float(buf, 16, yaw_rudder);
137 _mav_put_float(buf, 20, throttle);
138 _mav_put_float(buf, 24, aux1);
139 _mav_put_float(buf, 28, aux2);
140 _mav_put_float(buf, 32, aux3);
141 _mav_put_float(buf, 36, aux4);
142 _mav_put_uint8_t(buf, 40, mode);
143 _mav_put_uint8_t(buf, 41, nav_mode);
145 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
160 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
163 msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
164 #if MAVLINK_CRC_EXTRA
165 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
167 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
179 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)
181 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);
193 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)
195 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);
214 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
216 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)
218 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
219 char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN];
220 _mav_put_uint64_t(buf, 0, time_usec);
221 _mav_put_float(buf, 8, roll_ailerons);
222 _mav_put_float(buf, 12, pitch_elevator);
223 _mav_put_float(buf, 16, yaw_rudder);
224 _mav_put_float(buf, 20, throttle);
225 _mav_put_float(buf, 24, aux1);
226 _mav_put_float(buf, 28, aux2);
227 _mav_put_float(buf, 32, aux3);
228 _mav_put_float(buf, 36, aux4);
229 _mav_put_uint8_t(buf, 40, mode);
230 _mav_put_uint8_t(buf, 41, nav_mode);
232 #if MAVLINK_CRC_EXTRA
233 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
235 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
251 #if MAVLINK_CRC_EXTRA
252 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (
const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
254 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (
const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
259 #if MAVLINK_MSG_ID_HIL_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
267 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)
269 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
270 char *buf = (
char *)msgbuf;
271 _mav_put_uint64_t(buf, 0, time_usec);
272 _mav_put_float(buf, 8, roll_ailerons);
273 _mav_put_float(buf, 12, pitch_elevator);
274 _mav_put_float(buf, 16, yaw_rudder);
275 _mav_put_float(buf, 20, throttle);
276 _mav_put_float(buf, 24, aux1);
277 _mav_put_float(buf, 28, aux2);
278 _mav_put_float(buf, 32, aux3);
279 _mav_put_float(buf, 36, aux4);
280 _mav_put_uint8_t(buf, 40, mode);
281 _mav_put_uint8_t(buf, 41, nav_mode);
283 #if MAVLINK_CRC_EXTRA
284 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
286 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
302 #if MAVLINK_CRC_EXTRA
303 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (
const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
305 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (
const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
321 static inline uint64_t mavlink_msg_hil_controls_get_time_usec(
const mavlink_message_t* msg)
323 return _MAV_RETURN_uint64_t(msg, 0);
331 static inline float mavlink_msg_hil_controls_get_roll_ailerons(
const mavlink_message_t* msg)
333 return _MAV_RETURN_float(msg, 8);
341 static inline float mavlink_msg_hil_controls_get_pitch_elevator(
const mavlink_message_t* msg)
343 return _MAV_RETURN_float(msg, 12);
351 static inline float mavlink_msg_hil_controls_get_yaw_rudder(
const mavlink_message_t* msg)
353 return _MAV_RETURN_float(msg, 16);
361 static inline float mavlink_msg_hil_controls_get_throttle(
const mavlink_message_t* msg)
363 return _MAV_RETURN_float(msg, 20);
371 static inline float mavlink_msg_hil_controls_get_aux1(
const mavlink_message_t* msg)
373 return _MAV_RETURN_float(msg, 24);
381 static inline float mavlink_msg_hil_controls_get_aux2(
const mavlink_message_t* msg)
383 return _MAV_RETURN_float(msg, 28);
391 static inline float mavlink_msg_hil_controls_get_aux3(
const mavlink_message_t* msg)
393 return _MAV_RETURN_float(msg, 32);
401 static inline float mavlink_msg_hil_controls_get_aux4(
const mavlink_message_t* msg)
403 return _MAV_RETURN_float(msg, 36);
411 static inline uint8_t mavlink_msg_hil_controls_get_mode(
const mavlink_message_t* msg)
413 return _MAV_RETURN_uint8_t(msg, 40);
421 static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(
const mavlink_message_t* msg)
423 return _MAV_RETURN_uint8_t(msg, 41);
432 static inline void mavlink_msg_hil_controls_decode(
const mavlink_message_t* msg,
mavlink_hil_controls_t* hil_controls)
434 #if MAVLINK_NEED_BYTE_SWAP
435 hil_controls->
time_usec = mavlink_msg_hil_controls_get_time_usec(msg);
436 hil_controls->
roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg);
437 hil_controls->
pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg);
438 hil_controls->
yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg);
439 hil_controls->
throttle = mavlink_msg_hil_controls_get_throttle(msg);
440 hil_controls->
aux1 = mavlink_msg_hil_controls_get_aux1(msg);
441 hil_controls->
aux2 = mavlink_msg_hil_controls_get_aux2(msg);
442 hil_controls->
aux3 = mavlink_msg_hil_controls_get_aux3(msg);
443 hil_controls->
aux4 = mavlink_msg_hil_controls_get_aux4(msg);
444 hil_controls->
mode = mavlink_msg_hil_controls_get_mode(msg);
445 hil_controls->
nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg);
447 memcpy(hil_controls, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
uint8_t mode
System mode (MAV_MODE)
Definition: mavlink_msg_hil_controls.h:16
uint64_t time_usec
Timestamp (microseconds since UNIX epoch or microseconds since system boot)
Definition: mavlink_msg_hil_controls.h:7
float aux3
Aux 3, -1 .. 1.
Definition: mavlink_msg_hil_controls.h:14
float roll_ailerons
Control output -1 .. 1.
Definition: mavlink_msg_hil_controls.h:8
float aux2
Aux 2, -1 .. 1.
Definition: mavlink_msg_hil_controls.h:13
float aux1
Aux 1, -1 .. 1.
Definition: mavlink_msg_hil_controls.h:12
float throttle
Throttle 0 .. 1.
Definition: mavlink_msg_hil_controls.h:11
float pitch_elevator
Control output -1 .. 1.
Definition: mavlink_msg_hil_controls.h:9
Definition: mavlink_msg_hil_controls.h:5
float yaw_rudder
Control output -1 .. 1.
Definition: mavlink_msg_hil_controls.h:10
float aux4
Aux 4, -1 .. 1.
Definition: mavlink_msg_hil_controls.h:15
uint8_t nav_mode
Navigation mode (MAV_NAV_MODE)
Definition: mavlink_msg_hil_controls.h:17