3 #define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_INFO 203 12 #define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_INFO_LEN 22 13 #define MAVLINK_MSG_ID_203_LEN 22 15 #define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_INFO_CRC 123 16 #define MAVLINK_MSG_ID_203_CRC 123 18 #define MAVLINK_MSG_ROSFLIGHT_CONFIG_INFO_FIELD_NAME_LEN 20 20 #define MAVLINK_MESSAGE_INFO_ROSFLIGHT_CONFIG_INFO { \ 21 "ROSFLIGHT_CONFIG_INFO", \ 23 { { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rosflight_config_info_t, device) }, \ 24 { "config", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_rosflight_config_info_t, config) }, \ 25 { "name", NULL, MAVLINK_TYPE_UINT8_T, 20, 2, offsetof(mavlink_rosflight_config_info_t, name) }, \ 44 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 78 mavlink_message_t* msg,
81 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 138 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 142 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 147 #if MAVLINK_CRC_EXTRA 157 #if MAVLINK_CRC_EXTRA 165 #if MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_INFO_LEN <= MAVLINK_MAX_PAYLOAD_LEN 173 static inline void mavlink_msg_rosflight_config_info_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint8_t
device, uint8_t
config,
const uint8_t *
name)
175 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 176 char *buf = (
char *)msgbuf;
180 #if MAVLINK_CRC_EXTRA 190 #if MAVLINK_CRC_EXTRA 242 #if MAVLINK_NEED_BYTE_SWAP static uint16_t mavlink_msg_rosflight_config_info_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t device, uint8_t config, const uint8_t *name)
Pack a rosflight_config_info message on a channel.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_INFO
static uint16_t mavlink_msg_rosflight_config_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t device, uint8_t config, const uint8_t *name)
Pack a rosflight_config_info 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)
static void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
static uint16_t mavlink_msg_rosflight_config_info_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_rosflight_config_info_t *rosflight_config_info)
Encode a rosflight_config_info struct on a channel.
static uint8_t mavlink_msg_rosflight_config_info_get_device(const mavlink_message_t *msg)
Send a rosflight_config_info message.
#define _MAV_PAYLOAD_NON_CONST(msg)
#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_INFO_LEN
#define _MAV_PAYLOAD(msg)
static uint16_t mavlink_msg_rosflight_config_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_rosflight_config_info_t *rosflight_config_info)
Encode a rosflight_config_info struct.
static void mavlink_msg_rosflight_config_info_decode(const mavlink_message_t *msg, mavlink_rosflight_config_info_t *rosflight_config_info)
Decode a rosflight_config_info message into a struct.
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)
static uint16_t mavlink_msg_rosflight_config_info_get_name(const mavlink_message_t *msg, uint8_t *name)
Get field name from rosflight_config_info 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_rosflight_config_info_get_config(const mavlink_message_t *msg)
Get field config from rosflight_config_info message.
#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_INFO_CRC
struct __mavlink_rosflight_config_info_t mavlink_rosflight_config_info_t