3 #define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_STATUS 204 13 #define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_STATUS_LEN 53 14 #define MAVLINK_MSG_ID_204_LEN 53 16 #define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_STATUS_CRC 116 17 #define MAVLINK_MSG_ID_204_CRC 116 19 #define MAVLINK_MSG_ROSFLIGHT_CONFIG_STATUS_FIELD_ERROR_MESSAGE_LEN 50 21 #define MAVLINK_MESSAGE_INFO_ROSFLIGHT_CONFIG_STATUS { \ 22 "ROSFLIGHT_CONFIG_STATUS", \ 24 { { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rosflight_config_status_t, device) }, \ 25 { "success", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_rosflight_config_status_t, success) }, \ 26 { "reboot_required", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_rosflight_config_status_t, reboot_required) }, \ 27 { "error_message", NULL, MAVLINK_TYPE_UINT8_T, 50, 3, offsetof(mavlink_rosflight_config_status_t, error_message) }, \ 47 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 84 mavlink_message_t* msg,
87 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 104 #if MAVLINK_CRC_EXTRA 147 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 151 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 157 #if MAVLINK_CRC_EXTRA 168 #if MAVLINK_CRC_EXTRA 176 #if MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN 186 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 187 char *buf = (
char *)msgbuf;
192 #if MAVLINK_CRC_EXTRA 203 #if MAVLINK_CRC_EXTRA 265 #if MAVLINK_NEED_BYTE_SWAP static uint16_t mavlink_msg_rosflight_config_status_get_error_message(const mavlink_message_t *msg, uint8_t *error_message)
Get field error_message from rosflight_config_status message.
static uint16_t mavlink_msg_rosflight_config_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t device, uint8_t success, uint8_t reboot_required, const uint8_t *error_message)
Pack a rosflight_config_status message on a channel.
#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_STATUS_LEN
static uint8_t mavlink_msg_rosflight_config_status_get_device(const mavlink_message_t *msg)
Send a rosflight_config_status message.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
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 uint8_t mavlink_msg_rosflight_config_status_get_success(const mavlink_message_t *msg)
Get field success from rosflight_config_status 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)
#define _MAV_PAYLOAD_NON_CONST(msg)
static void mavlink_msg_rosflight_config_status_decode(const mavlink_message_t *msg, mavlink_rosflight_config_status_t *rosflight_config_status)
Decode a rosflight_config_status message into a struct.
#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_STATUS_CRC
#define _MAV_PAYLOAD(msg)
static uint16_t mavlink_msg_rosflight_config_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t device, uint8_t success, uint8_t reboot_required, const uint8_t *error_message)
Pack a rosflight_config_status message.
static uint16_t mavlink_msg_rosflight_config_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_rosflight_config_status_t *rosflight_config_status)
Encode a rosflight_config_status struct.
static void mav_array_memcpy(void *dest, const void *src, size_t n)
#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_STATUS
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_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_rosflight_config_status_t *rosflight_config_status)
Encode a rosflight_config_status struct on a channel.
uint8_t error_message[50]
struct __mavlink_rosflight_config_status_t mavlink_rosflight_config_status_t
static uint8_t mavlink_msg_rosflight_config_status_get_reboot_required(const mavlink_message_t *msg)
Get field reboot_required from rosflight_config_status 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.