3 #define MAVLINK_MSG_ID_SERIAL_CONTROL 126 15 #define MAVLINK_MSG_ID_SERIAL_CONTROL_LEN 79 16 #define MAVLINK_MSG_ID_126_LEN 79 18 #define MAVLINK_MSG_ID_SERIAL_CONTROL_CRC 220 19 #define MAVLINK_MSG_ID_126_CRC 220 21 #define MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN 70 23 #define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL { \ 26 { { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \ 27 { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \ 28 { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \ 29 { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \ 30 { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \ 31 { "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \ 53 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 96 mavlink_message_t* msg,
99 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 120 #if MAVLINK_CRC_EXTRA 165 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 169 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 177 #if MAVLINK_CRC_EXTRA 190 #if MAVLINK_CRC_EXTRA 198 #if MAVLINK_MSG_ID_SERIAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN 208 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 209 char *buf = (
char *)msgbuf;
216 #if MAVLINK_CRC_EXTRA 229 #if MAVLINK_CRC_EXTRA 270 return _MAV_RETURN_uint16_t(msg, 4);
280 return _MAV_RETURN_uint32_t(msg, 0);
311 #if MAVLINK_NEED_BYTE_SWAP static uint16_t mavlink_msg_serial_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_serial_control_t *serial_control)
Encode a serial_control struct on a channel.
static uint8_t mavlink_msg_serial_control_get_count(const mavlink_message_t *msg)
Get field count from serial_control message.
#define MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
static uint8_t mavlink_msg_serial_control_get_device(const mavlink_message_t *msg)
Send a serial_control message.
static uint16_t mavlink_msg_serial_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data)
Pack a serial_control message.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static uint8_t mavlink_msg_serial_control_get_flags(const mavlink_message_t *msg)
Get field flags from serial_control 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.
static uint32_t mavlink_msg_serial_control_get_baudrate(const mavlink_message_t *msg)
Get field baudrate from serial_control message.
#define _mav_put_uint8_t(buf, wire_offset, b)
static void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
struct __mavlink_serial_control_t mavlink_serial_control_t
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint16_t mavlink_msg_serial_control_get_timeout(const mavlink_message_t *msg)
Get field timeout from serial_control message.
static uint16_t mavlink_msg_serial_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_serial_control_t *serial_control)
Encode a serial_control struct.
#define _MAV_PAYLOAD(msg)
#define MAVLINK_MSG_ID_SERIAL_CONTROL
static void mav_array_memcpy(void *dest, const void *src, size_t n)
static uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value, uint8_t array_length, uint8_t wire_offset)
#define MAVLINK_MSG_ID_SERIAL_CONTROL_CRC
static void mavlink_msg_serial_control_decode(const mavlink_message_t *msg, mavlink_serial_control_t *serial_control)
Decode a serial_control message into a struct.
#define _mav_put_uint16_t(buf, wire_offset, b)
static uint16_t mavlink_msg_serial_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data)
Pack a serial_control message on a channel.
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 uint16_t mavlink_msg_serial_control_get_data(const mavlink_message_t *msg, uint8_t *data)
Get field data from serial_control message.
#define _mav_put_uint32_t(buf, wire_offset, b)