3 #define MAVLINK_MSG_ID_PARAM_MAP_RC 50 18 #define MAVLINK_MSG_ID_PARAM_MAP_RC_LEN 37 19 #define MAVLINK_MSG_ID_50_LEN 37 21 #define MAVLINK_MSG_ID_PARAM_MAP_RC_CRC 78 22 #define MAVLINK_MSG_ID_50_CRC 78 24 #define MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN 16 26 #define MAVLINK_MESSAGE_INFO_PARAM_MAP_RC { \ 29 { { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \ 30 { "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \ 31 { "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \ 32 { "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \ 33 { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \ 34 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \ 35 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \ 36 { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \ 37 { "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \ 62 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 114 mavlink_message_t* msg,
117 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 144 #if MAVLINK_CRC_EXTRA 161 return mavlink_msg_param_map_rc_pack(system_id, component_id, msg, param_map_rc->
target_system, param_map_rc->
target_component, param_map_rc->
param_id, param_map_rc->
param_index, param_map_rc->
parameter_rc_channel_index, param_map_rc->
param_value0, param_map_rc->
scale, param_map_rc->
param_value_min, param_map_rc->
param_value_max);
175 return mavlink_msg_param_map_rc_pack_chan(system_id, component_id, chan, msg, param_map_rc->
target_system, param_map_rc->
target_component, param_map_rc->
param_id, param_map_rc->
param_index, param_map_rc->
parameter_rc_channel_index, param_map_rc->
param_value0, param_map_rc->
scale, param_map_rc->
param_value_min, param_map_rc->
param_value_max);
192 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 196 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 207 #if MAVLINK_CRC_EXTRA 223 #if MAVLINK_CRC_EXTRA 231 #if MAVLINK_MSG_ID_PARAM_MAP_RC_LEN <= MAVLINK_MAX_PAYLOAD_LEN 239 static inline void mavlink_msg_param_map_rc_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint8_t
target_system, uint8_t
target_component,
const char *
param_id, int16_t
param_index, uint8_t
parameter_rc_channel_index,
float param_value0,
float scale,
float param_value_min,
float param_value_max)
241 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 242 char *buf = (
char *)msgbuf;
252 #if MAVLINK_CRC_EXTRA 268 #if MAVLINK_CRC_EXTRA 319 return _MAV_RETURN_int16_t(msg, 16);
339 return _MAV_RETURN_float(msg, 0);
349 return _MAV_RETURN_float(msg, 4);
359 return _MAV_RETURN_float(msg, 8);
369 return _MAV_RETURN_float(msg, 12);
380 #if MAVLINK_NEED_BYTE_SWAP #define _mav_put_float(buf, wire_offset, b)
static uint16_t mavlink_msg_param_map_rc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_param_map_rc_t *param_map_rc)
Encode a param_map_rc struct.
#define MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
static uint16_t mavlink_msg_param_map_rc_get_param_id(const mavlink_message_t *msg, char *param_id)
Get field param_id from param_map_rc message.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static uint8_t mavlink_msg_param_map_rc_get_target_system(const mavlink_message_t *msg)
Send a param_map_rc 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.
static float mavlink_msg_param_map_rc_get_scale(const mavlink_message_t *msg)
Get field scale from param_map_rc message.
#define _mav_put_uint8_t(buf, wire_offset, b)
static uint16_t mavlink_msg_param_map_rc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_param_map_rc_t *param_map_rc)
Encode a param_map_rc struct on a channel.
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint16_t mavlink_msg_param_map_rc_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, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max)
Pack a param_map_rc message on a channel.
static void mavlink_msg_param_map_rc_decode(const mavlink_message_t *msg, mavlink_param_map_rc_t *param_map_rc)
Decode a param_map_rc message into a struct.
static uint8_t mavlink_msg_param_map_rc_get_parameter_rc_channel_index(const mavlink_message_t *msg)
Get field parameter_rc_channel_index from param_map_rc message.
struct __mavlink_param_map_rc_t mavlink_param_map_rc_t
#define _MAV_PAYLOAD(msg)
static int16_t mavlink_msg_param_map_rc_get_param_index(const mavlink_message_t *msg)
Get field param_index from param_map_rc message.
#define MAVLINK_MSG_ID_PARAM_MAP_RC
static float mavlink_msg_param_map_rc_get_param_value_max(const mavlink_message_t *msg)
Get field param_value_max from param_map_rc message.
uint8_t parameter_rc_channel_index
static float mavlink_msg_param_map_rc_get_param_value_min(const mavlink_message_t *msg)
Get field param_value_min from param_map_rc message.
static void mav_array_memcpy(void *dest, const void *src, size_t n)
static float mavlink_msg_param_map_rc_get_param_value0(const mavlink_message_t *msg)
Get field param_value0 from param_map_rc message.
static uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value, uint8_t array_length, uint8_t wire_offset)
static uint16_t mavlink_msg_param_map_rc_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, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max)
Pack a param_map_rc message.
static void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
#define MAVLINK_MSG_ID_PARAM_MAP_RC_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.
#define _mav_put_int16_t(buf, wire_offset, b)
static uint8_t mavlink_msg_param_map_rc_get_target_component(const mavlink_message_t *msg)
Get field target_component from param_map_rc message.