3 #define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70 19 #define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18 20 #define MAVLINK_MSG_ID_70_LEN 18 22 #define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC 124 23 #define MAVLINK_MSG_ID_70_CRC 124 27 #define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \ 28 "RC_CHANNELS_OVERRIDE", \ 30 { { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ 31 { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ 32 { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ 33 { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ 34 { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \ 35 { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ 36 { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ 37 { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ 38 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ 39 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ 65 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 122 mavlink_message_t* msg,
125 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 156 #if MAVLINK_CRC_EXTRA 173 return mavlink_msg_rc_channels_override_pack(system_id, component_id, msg, rc_channels_override->
target_system, rc_channels_override->
target_component, rc_channels_override->
chan1_raw, rc_channels_override->
chan2_raw, rc_channels_override->
chan3_raw, rc_channels_override->
chan4_raw, rc_channels_override->
chan5_raw, rc_channels_override->
chan6_raw, rc_channels_override->
chan7_raw, rc_channels_override->
chan8_raw);
187 return mavlink_msg_rc_channels_override_pack_chan(system_id, component_id, chan, msg, rc_channels_override->
target_system, rc_channels_override->
target_component, rc_channels_override->
chan1_raw, rc_channels_override->
chan2_raw, rc_channels_override->
chan3_raw, rc_channels_override->
chan4_raw, rc_channels_override->
chan5_raw, rc_channels_override->
chan6_raw, rc_channels_override->
chan7_raw, rc_channels_override->
chan8_raw);
205 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 207 static inline void mavlink_msg_rc_channels_override_send(
mavlink_channel_t chan, uint8_t
target_system, uint8_t
target_component, uint16_t
chan1_raw, uint16_t
chan2_raw, uint16_t
chan3_raw, uint16_t
chan4_raw, uint16_t
chan5_raw, uint16_t
chan6_raw, uint16_t
chan7_raw, uint16_t
chan8_raw)
209 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 222 #if MAVLINK_CRC_EXTRA 240 #if MAVLINK_CRC_EXTRA 248 #if MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN 256 static inline void mavlink_msg_rc_channels_override_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint8_t
target_system, uint8_t
target_component, uint16_t
chan1_raw, uint16_t
chan2_raw, uint16_t
chan3_raw, uint16_t
chan4_raw, uint16_t
chan5_raw, uint16_t
chan6_raw, uint16_t
chan7_raw, uint16_t
chan8_raw)
258 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 259 char *buf = (
char *)msgbuf;
271 #if MAVLINK_CRC_EXTRA 289 #if MAVLINK_CRC_EXTRA 330 return _MAV_RETURN_uint16_t(msg, 0);
340 return _MAV_RETURN_uint16_t(msg, 2);
350 return _MAV_RETURN_uint16_t(msg, 4);
360 return _MAV_RETURN_uint16_t(msg, 6);
370 return _MAV_RETURN_uint16_t(msg, 8);
380 return _MAV_RETURN_uint16_t(msg, 10);
390 return _MAV_RETURN_uint16_t(msg, 12);
400 return _MAV_RETURN_uint16_t(msg, 14);
411 #if MAVLINK_NEED_BYTE_SWAP static uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t *msg)
Get field chan2_raw from rc_channels_override message.
#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC
static uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t *msg)
Get field chan8_raw from rc_channels_override message.
static uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t *msg)
Get field chan7_raw from rc_channels_override message.
static uint8_t mavlink_msg_rc_channels_override_get_target_component(const mavlink_message_t *msg)
Get field target_component from rc_channels_override message.
static uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t *msg)
Get field chan3_raw from rc_channels_override message.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_rc_channels_override_t *rc_channels_override)
Encode a rc_channels_override struct.
static uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t *msg)
Get field chan6_raw from rc_channels_override message.
#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN
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.
static uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t *msg)
Get field chan1_raw from rc_channels_override message.
#define _mav_put_uint8_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw)
Pack a rc_channels_override message.
#define _MAV_PAYLOAD(msg)
static void mavlink_msg_rc_channels_override_decode(const mavlink_message_t *msg, mavlink_rc_channels_override_t *rc_channels_override)
Decode a rc_channels_override message into a struct.
struct __mavlink_rc_channels_override_t mavlink_rc_channels_override_t
static uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t *msg)
Get field chan4_raw from rc_channels_override message.
static uint16_t mavlink_msg_rc_channels_override_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_rc_channels_override_t *rc_channels_override)
Encode a rc_channels_override struct on a channel.
static uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw)
Pack a rc_channels_override message on a channel.
#define _mav_put_uint16_t(buf, wire_offset, b)
static uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t *msg)
Get field chan5_raw from rc_channels_override message.
static uint8_t mavlink_msg_rc_channels_override_get_target_system(const mavlink_message_t *msg)
Send a rc_channels_override 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.
#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE