3 #define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_REQUEST 200 10 #define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_REQUEST_LEN 1 11 #define MAVLINK_MSG_ID_200_LEN 1 13 #define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_REQUEST_CRC 174 14 #define MAVLINK_MSG_ID_200_CRC 174 18 #define MAVLINK_MESSAGE_INFO_ROSFLIGHT_CONFIG_REQUEST { \ 19 "ROSFLIGHT_CONFIG_REQUEST", \ 21 { { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rosflight_config_request_t, device) }, \ 38 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 68 mavlink_message_t* msg,
71 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 124 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 128 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 132 #if MAVLINK_CRC_EXTRA 141 #if MAVLINK_CRC_EXTRA 149 #if MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN 157 static inline void mavlink_msg_rosflight_config_request_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint8_t
device)
159 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 160 char *buf = (
char *)msgbuf;
163 #if MAVLINK_CRC_EXTRA 172 #if MAVLINK_CRC_EXTRA 204 #if MAVLINK_NEED_BYTE_SWAP #define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_REQUEST
static uint16_t mavlink_msg_rosflight_config_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t device)
Pack a rosflight_config_request message on a channel.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static uint16_t mavlink_msg_rosflight_config_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_rosflight_config_request_t *rosflight_config_request)
Encode a rosflight_config_request struct on a channel.
static uint8_t mavlink_msg_rosflight_config_request_get_device(const mavlink_message_t *msg)
Send a rosflight_config_request message.
static void mavlink_msg_rosflight_config_request_decode(const mavlink_message_t *msg, mavlink_rosflight_config_request_t *rosflight_config_request)
Decode a rosflight_config_request message into a struct.
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_PAYLOAD_NON_CONST(msg)
#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_REQUEST_CRC
#define _MAV_PAYLOAD(msg)
static uint16_t mavlink_msg_rosflight_config_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_rosflight_config_request_t *rosflight_config_request)
Encode a rosflight_config_request struct.
static uint16_t mavlink_msg_rosflight_config_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t device)
Pack a rosflight_config_request message.
#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_REQUEST_LEN
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.
struct __mavlink_rosflight_config_request_t mavlink_rosflight_config_request_t