3 #define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20 13 #define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20 14 #define MAVLINK_MSG_ID_20_LEN 20 16 #define MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC 214 17 #define MAVLINK_MSG_ID_20_CRC 214 19 #define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 16 21 #define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \ 22 "PARAM_REQUEST_READ", \ 24 { { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ 25 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ 26 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \ 27 { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \ 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_PARAM_REQUEST_READ_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 254 return _MAV_RETURN_int16_t(msg, 0);
265 #if MAVLINK_NEED_BYTE_SWAP static void mavlink_msg_param_request_read_decode(const mavlink_message_t *msg, mavlink_param_request_read_t *param_request_read)
Decode a param_request_read message into a struct.
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
#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.
#define _mav_put_uint8_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index)
Pack a param_request_read message on a channel.
static int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t *msg)
Get field param_index from param_request_read message.
static uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t *msg)
Send a param_request_read message.
#define _MAV_PAYLOAD(msg)
static uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t *msg, char *param_id)
Get field param_id from param_request_read message.
struct __mavlink_param_request_read_t mavlink_param_request_read_t
static uint16_t mavlink_msg_param_request_read_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_param_request_read_t *param_request_read)
Encode a param_request_read struct on a channel.
static uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_param_request_read_t *param_request_read)
Encode a param_request_read struct.
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ
static uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t *msg)
Get field target_component from param_request_read message.
static void mav_array_memcpy(void *dest, const void *src, size_t n)
static uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value, uint8_t array_length, uint8_t wire_offset)
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC
static void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
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.
#define _mav_put_int16_t(buf, wire_offset, b)
static uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index)
Pack a param_request_read message.