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) }, \ 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 101 #if MAVLINK_CRC_EXTRA 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 164 #if MAVLINK_CRC_EXTRA 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);
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 232 #if MAVLINK_CRC_EXTRA 251 #if MAVLINK_CRC_EXTRA 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;
283 #if MAVLINK_CRC_EXTRA 302 #if MAVLINK_CRC_EXTRA 323 return _MAV_RETURN_uint64_t(msg, 0);
333 return _MAV_RETURN_float(msg, 8);
343 return _MAV_RETURN_float(msg, 12);
353 return _MAV_RETURN_float(msg, 16);
363 return _MAV_RETURN_float(msg, 20);
373 return _MAV_RETURN_float(msg, 24);
383 return _MAV_RETURN_float(msg, 28);
393 return _MAV_RETURN_float(msg, 32);
403 return _MAV_RETURN_float(msg, 36);
434 #if MAVLINK_NEED_BYTE_SWAP struct __mavlink_hil_controls_t mavlink_hil_controls_t
#define _mav_put_float(buf, wire_offset, b)
static uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, 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)
Pack a hil_controls message.
#define MAVLINK_MSG_ID_HIL_CONTROLS
static uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t *msg)
Send a hil_controls message.
static 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)
Encode a hil_controls struct.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t *msg)
Get field aux4 from hil_controls message.
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
#define _mav_put_uint8_t(buf, wire_offset, b)
#define _mav_put_uint64_t(buf, wire_offset, b)
static uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t *msg)
Get field nav_mode from hil_controls message.
#define _MAV_PAYLOAD_NON_CONST(msg)
static float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t *msg)
Get field throttle from hil_controls message.
static float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t *msg)
Get field yaw_rudder from hil_controls message.
#define _MAV_PAYLOAD(msg)
static float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t *msg)
Get field pitch_elevator from hil_controls message.
#define MAVLINK_MSG_ID_HIL_CONTROLS_LEN
static void mavlink_msg_hil_controls_decode(const mavlink_message_t *msg, mavlink_hil_controls_t *hil_controls)
Decode a hil_controls message into a struct.
static uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, 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)
Pack a hil_controls message on a channel.
#define MAVLINK_MSG_ID_HIL_CONTROLS_CRC
static float mavlink_msg_hil_controls_get_aux1(const mavlink_message_t *msg)
Get field aux1 from hil_controls message.
static 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)
Encode a hil_controls struct on a channel.
static float mavlink_msg_hil_controls_get_aux3(const mavlink_message_t *msg)
Get field aux3 from hil_controls message.
static float mavlink_msg_hil_controls_get_aux2(const mavlink_message_t *msg)
Get field aux2 from hil_controls message.
static float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t *msg)
Get field roll_ailerons from hil_controls message.
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
static uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t *msg)
Get field mode from hil_controls message.