2 // MESSAGE PARAM_MAP_RC PACKING
4 #define MAVLINK_MSG_ID_PARAM_MAP_RC 50
7 typedef struct __mavlink_param_map_rc_t
{
8 float param_value0
; /*< Initial parameter value*/
9 float scale
; /*< Scale, maps the RC range [-1, 1] to a parameter value*/
10 float param_value_min
; /*< Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)*/
11 float param_value_max
; /*< Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)*/
12 int16_t param_index
; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.*/
13 uint8_t target_system
; /*< System ID*/
14 uint8_t target_component
; /*< Component ID*/
15 char param_id
[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/
16 uint8_t parameter_rc_channel_index
; /*< Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.*/
17 } mavlink_param_map_rc_t
;
19 #define MAVLINK_MSG_ID_PARAM_MAP_RC_LEN 37
20 #define MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN 37
21 #define MAVLINK_MSG_ID_50_LEN 37
22 #define MAVLINK_MSG_ID_50_MIN_LEN 37
24 #define MAVLINK_MSG_ID_PARAM_MAP_RC_CRC 78
25 #define MAVLINK_MSG_ID_50_CRC 78
27 #define MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN 16
29 #if MAVLINK_COMMAND_24BIT
30 #define MAVLINK_MESSAGE_INFO_PARAM_MAP_RC { \
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 { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \
38 { "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \
39 { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \
40 { "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \
41 { "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \
42 { "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \
46 #define MAVLINK_MESSAGE_INFO_PARAM_MAP_RC { \
49 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \
50 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \
51 { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \
52 { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \
53 { "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \
54 { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \
55 { "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \
56 { "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \
57 { "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \
63 * @brief Pack a param_map_rc message
64 * @param system_id ID of this system
65 * @param component_id ID of this component (e.g. 200 for IMU)
66 * @param msg The MAVLink message to compress the data into
68 * @param target_system System ID
69 * @param target_component Component ID
70 * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
71 * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.
72 * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.
73 * @param param_value0 Initial parameter value
74 * @param scale Scale, maps the RC range [-1, 1] to a parameter value
75 * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)
76 * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)
77 * @return length of the message in bytes (excluding serial stream start sign)
79 static inline uint16_t mavlink_msg_param_map_rc_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
80 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
)
82 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
83 char buf
[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
];
84 _mav_put_float(buf
, 0, param_value0
);
85 _mav_put_float(buf
, 4, scale
);
86 _mav_put_float(buf
, 8, param_value_min
);
87 _mav_put_float(buf
, 12, param_value_max
);
88 _mav_put_int16_t(buf
, 16, param_index
);
89 _mav_put_uint8_t(buf
, 18, target_system
);
90 _mav_put_uint8_t(buf
, 19, target_component
);
91 _mav_put_uint8_t(buf
, 36, parameter_rc_channel_index
);
92 _mav_put_char_array(buf
, 20, param_id
, 16);
93 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
);
95 mavlink_param_map_rc_t packet
;
96 packet
.param_value0
= param_value0
;
98 packet
.param_value_min
= param_value_min
;
99 packet
.param_value_max
= param_value_max
;
100 packet
.param_index
= param_index
;
101 packet
.target_system
= target_system
;
102 packet
.target_component
= target_component
;
103 packet
.parameter_rc_channel_index
= parameter_rc_channel_index
;
104 mav_array_memcpy(packet
.param_id
, param_id
, sizeof(char)*16);
105 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
);
108 msg
->msgid
= MAVLINK_MSG_ID_PARAM_MAP_RC
;
109 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN
, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC
);
113 * @brief Pack a param_map_rc message on a channel
114 * @param system_id ID of this system
115 * @param component_id ID of this component (e.g. 200 for IMU)
116 * @param chan The MAVLink channel this message will be sent over
117 * @param msg The MAVLink message to compress the data into
118 * @param target_system System ID
119 * @param target_component Component ID
120 * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
121 * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.
122 * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.
123 * @param param_value0 Initial parameter value
124 * @param scale Scale, maps the RC range [-1, 1] to a parameter value
125 * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)
126 * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)
127 * @return length of the message in bytes (excluding serial stream start sign)
129 static inline uint16_t mavlink_msg_param_map_rc_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
130 mavlink_message_t
* msg
,
131 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
)
133 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
134 char buf
[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
];
135 _mav_put_float(buf
, 0, param_value0
);
136 _mav_put_float(buf
, 4, scale
);
137 _mav_put_float(buf
, 8, param_value_min
);
138 _mav_put_float(buf
, 12, param_value_max
);
139 _mav_put_int16_t(buf
, 16, param_index
);
140 _mav_put_uint8_t(buf
, 18, target_system
);
141 _mav_put_uint8_t(buf
, 19, target_component
);
142 _mav_put_uint8_t(buf
, 36, parameter_rc_channel_index
);
143 _mav_put_char_array(buf
, 20, param_id
, 16);
144 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
);
146 mavlink_param_map_rc_t packet
;
147 packet
.param_value0
= param_value0
;
148 packet
.scale
= scale
;
149 packet
.param_value_min
= param_value_min
;
150 packet
.param_value_max
= param_value_max
;
151 packet
.param_index
= param_index
;
152 packet
.target_system
= target_system
;
153 packet
.target_component
= target_component
;
154 packet
.parameter_rc_channel_index
= parameter_rc_channel_index
;
155 mav_array_memcpy(packet
.param_id
, param_id
, sizeof(char)*16);
156 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
);
159 msg
->msgid
= MAVLINK_MSG_ID_PARAM_MAP_RC
;
160 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN
, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC
);
164 * @brief Encode a param_map_rc struct
166 * @param system_id ID of this system
167 * @param component_id ID of this component (e.g. 200 for IMU)
168 * @param msg The MAVLink message to compress the data into
169 * @param param_map_rc C-struct to read the message contents from
171 static inline 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
)
173 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
);
177 * @brief Encode a param_map_rc struct on a channel
179 * @param system_id ID of this system
180 * @param component_id ID of this component (e.g. 200 for IMU)
181 * @param chan The MAVLink channel this message will be sent over
182 * @param msg The MAVLink message to compress the data into
183 * @param param_map_rc C-struct to read the message contents from
185 static inline 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
)
187 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
);
191 * @brief Send a param_map_rc message
192 * @param chan MAVLink channel to send the message
194 * @param target_system System ID
195 * @param target_component Component ID
196 * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
197 * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.
198 * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.
199 * @param param_value0 Initial parameter value
200 * @param scale Scale, maps the RC range [-1, 1] to a parameter value
201 * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)
202 * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)
204 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
206 static inline void mavlink_msg_param_map_rc_send(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
)
208 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
209 char buf
[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
];
210 _mav_put_float(buf
, 0, param_value0
);
211 _mav_put_float(buf
, 4, scale
);
212 _mav_put_float(buf
, 8, param_value_min
);
213 _mav_put_float(buf
, 12, param_value_max
);
214 _mav_put_int16_t(buf
, 16, param_index
);
215 _mav_put_uint8_t(buf
, 18, target_system
);
216 _mav_put_uint8_t(buf
, 19, target_component
);
217 _mav_put_uint8_t(buf
, 36, parameter_rc_channel_index
);
218 _mav_put_char_array(buf
, 20, param_id
, 16);
219 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_MAP_RC
, buf
, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN
, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC
);
221 mavlink_param_map_rc_t packet
;
222 packet
.param_value0
= param_value0
;
223 packet
.scale
= scale
;
224 packet
.param_value_min
= param_value_min
;
225 packet
.param_value_max
= param_value_max
;
226 packet
.param_index
= param_index
;
227 packet
.target_system
= target_system
;
228 packet
.target_component
= target_component
;
229 packet
.parameter_rc_channel_index
= parameter_rc_channel_index
;
230 mav_array_memcpy(packet
.param_id
, param_id
, sizeof(char)*16);
231 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_MAP_RC
, (const char *)&packet
, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN
, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC
);
236 * @brief Send a param_map_rc message
237 * @param chan MAVLink channel to send the message
238 * @param struct The MAVLink struct to serialize
240 static inline void mavlink_msg_param_map_rc_send_struct(mavlink_channel_t chan
, const mavlink_param_map_rc_t
* param_map_rc
)
242 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
243 mavlink_msg_param_map_rc_send(chan
, 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
);
245 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_MAP_RC
, (const char *)param_map_rc
, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN
, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC
);
249 #if MAVLINK_MSG_ID_PARAM_MAP_RC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
251 This varient of _send() can be used to save stack space by re-using
252 memory from the receive buffer. The caller provides a
253 mavlink_message_t which is the size of a full mavlink message. This
254 is usually the receive buffer for the channel, and allows a reply to an
255 incoming message with minimum stack space usage.
257 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
)
259 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
260 char *buf
= (char *)msgbuf
;
261 _mav_put_float(buf
, 0, param_value0
);
262 _mav_put_float(buf
, 4, scale
);
263 _mav_put_float(buf
, 8, param_value_min
);
264 _mav_put_float(buf
, 12, param_value_max
);
265 _mav_put_int16_t(buf
, 16, param_index
);
266 _mav_put_uint8_t(buf
, 18, target_system
);
267 _mav_put_uint8_t(buf
, 19, target_component
);
268 _mav_put_uint8_t(buf
, 36, parameter_rc_channel_index
);
269 _mav_put_char_array(buf
, 20, param_id
, 16);
270 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_MAP_RC
, buf
, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN
, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC
);
272 mavlink_param_map_rc_t
*packet
= (mavlink_param_map_rc_t
*)msgbuf
;
273 packet
->param_value0
= param_value0
;
274 packet
->scale
= scale
;
275 packet
->param_value_min
= param_value_min
;
276 packet
->param_value_max
= param_value_max
;
277 packet
->param_index
= param_index
;
278 packet
->target_system
= target_system
;
279 packet
->target_component
= target_component
;
280 packet
->parameter_rc_channel_index
= parameter_rc_channel_index
;
281 mav_array_memcpy(packet
->param_id
, param_id
, sizeof(char)*16);
282 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_MAP_RC
, (const char *)packet
, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN
, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC
);
289 // MESSAGE PARAM_MAP_RC UNPACKING
293 * @brief Get field target_system from param_map_rc message
297 static inline uint8_t mavlink_msg_param_map_rc_get_target_system(const mavlink_message_t
* msg
)
299 return _MAV_RETURN_uint8_t(msg
, 18);
303 * @brief Get field target_component from param_map_rc message
305 * @return Component ID
307 static inline uint8_t mavlink_msg_param_map_rc_get_target_component(const mavlink_message_t
* msg
)
309 return _MAV_RETURN_uint8_t(msg
, 19);
313 * @brief Get field param_id from param_map_rc message
315 * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
317 static inline uint16_t mavlink_msg_param_map_rc_get_param_id(const mavlink_message_t
* msg
, char *param_id
)
319 return _MAV_RETURN_char_array(msg
, param_id
, 16, 20);
323 * @brief Get field param_index from param_map_rc message
325 * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.
327 static inline int16_t mavlink_msg_param_map_rc_get_param_index(const mavlink_message_t
* msg
)
329 return _MAV_RETURN_int16_t(msg
, 16);
333 * @brief Get field parameter_rc_channel_index from param_map_rc message
335 * @return Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.
337 static inline uint8_t mavlink_msg_param_map_rc_get_parameter_rc_channel_index(const mavlink_message_t
* msg
)
339 return _MAV_RETURN_uint8_t(msg
, 36);
343 * @brief Get field param_value0 from param_map_rc message
345 * @return Initial parameter value
347 static inline float mavlink_msg_param_map_rc_get_param_value0(const mavlink_message_t
* msg
)
349 return _MAV_RETURN_float(msg
, 0);
353 * @brief Get field scale from param_map_rc message
355 * @return Scale, maps the RC range [-1, 1] to a parameter value
357 static inline float mavlink_msg_param_map_rc_get_scale(const mavlink_message_t
* msg
)
359 return _MAV_RETURN_float(msg
, 4);
363 * @brief Get field param_value_min from param_map_rc message
365 * @return Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)
367 static inline float mavlink_msg_param_map_rc_get_param_value_min(const mavlink_message_t
* msg
)
369 return _MAV_RETURN_float(msg
, 8);
373 * @brief Get field param_value_max from param_map_rc message
375 * @return Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)
377 static inline float mavlink_msg_param_map_rc_get_param_value_max(const mavlink_message_t
* msg
)
379 return _MAV_RETURN_float(msg
, 12);
383 * @brief Decode a param_map_rc message into a struct
385 * @param msg The message to decode
386 * @param param_map_rc C-struct to decode the message contents into
388 static inline void mavlink_msg_param_map_rc_decode(const mavlink_message_t
* msg
, mavlink_param_map_rc_t
* param_map_rc
)
390 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
391 param_map_rc
->param_value0
= mavlink_msg_param_map_rc_get_param_value0(msg
);
392 param_map_rc
->scale
= mavlink_msg_param_map_rc_get_scale(msg
);
393 param_map_rc
->param_value_min
= mavlink_msg_param_map_rc_get_param_value_min(msg
);
394 param_map_rc
->param_value_max
= mavlink_msg_param_map_rc_get_param_value_max(msg
);
395 param_map_rc
->param_index
= mavlink_msg_param_map_rc_get_param_index(msg
);
396 param_map_rc
->target_system
= mavlink_msg_param_map_rc_get_target_system(msg
);
397 param_map_rc
->target_component
= mavlink_msg_param_map_rc_get_target_component(msg
);
398 mavlink_msg_param_map_rc_get_param_id(msg
, param_map_rc
->param_id
);
399 param_map_rc
->parameter_rc_channel_index
= mavlink_msg_param_map_rc_get_parameter_rc_channel_index(msg
);
401 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
? msg
->len
: MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
;
402 memset(param_map_rc
, 0, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN
);
403 memcpy(param_map_rc
, _MAV_PAYLOAD(msg
), len
);