3 #define MAVLINK_MSG_ID_RESOURCE_REQUEST 142 14 #define MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN 243 15 #define MAVLINK_MSG_ID_142_LEN 243 17 #define MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC 72 18 #define MAVLINK_MSG_ID_142_CRC 72 20 #define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_URI_LEN 120 21 #define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_STORAGE_LEN 120 23 #define MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST { \ 26 { { "request_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_resource_request_t, request_id) }, \ 27 { "uri_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_resource_request_t, uri_type) }, \ 28 { "uri", NULL, MAVLINK_TYPE_UINT8_T, 120, 2, offsetof(mavlink_resource_request_t, uri) }, \ 29 { "transfer_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 122, offsetof(mavlink_resource_request_t, transfer_type) }, \ 30 { "storage", NULL, MAVLINK_TYPE_UINT8_T, 120, 123, offsetof(mavlink_resource_request_t, storage) }, \ 51 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 91 mavlink_message_t* msg,
94 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 113 #if MAVLINK_CRC_EXTRA 157 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 161 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 168 #if MAVLINK_CRC_EXTRA 180 #if MAVLINK_CRC_EXTRA 188 #if MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN 198 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 199 char *buf = (
char *)msgbuf;
205 #if MAVLINK_CRC_EXTRA 217 #if MAVLINK_CRC_EXTRA 289 #if MAVLINK_NEED_BYTE_SWAP #define MAVLINK_MSG_ID_RESOURCE_REQUEST
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static uint16_t mavlink_msg_resource_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_resource_request_t *resource_request)
Encode a resource_request struct on a channel.
static uint8_t mavlink_msg_resource_request_get_transfer_type(const mavlink_message_t *msg)
Get field transfer_type from resource_request message.
static uint16_t mavlink_msg_resource_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage)
Pack a resource_request 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)
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint8_t mavlink_msg_resource_request_get_uri_type(const mavlink_message_t *msg)
Get field uri_type from resource_request message.
static uint16_t mavlink_msg_resource_request_get_uri(const mavlink_message_t *msg, uint8_t *uri)
Get field uri from resource_request message.
#define _MAV_PAYLOAD(msg)
static uint8_t mavlink_msg_resource_request_get_request_id(const mavlink_message_t *msg)
Send a resource_request message.
struct __mavlink_resource_request_t mavlink_resource_request_t
static uint16_t mavlink_msg_resource_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_resource_request_t *resource_request)
Encode a resource_request struct.
#define MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN
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_RESOURCE_REQUEST_CRC
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_resource_request_get_storage(const mavlink_message_t *msg, uint8_t *storage)
Get field storage from resource_request message.
static uint16_t mavlink_msg_resource_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage)
Pack a resource_request message on a channel.
static void mavlink_msg_resource_request_decode(const mavlink_message_t *msg, mavlink_resource_request_t *resource_request)
Decode a resource_request message into a struct.