2 // MESSAGE PARAM_REQUEST_READ PACKING
4 #define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20
7 typedef struct __mavlink_param_request_read_t
{
8 int16_t param_index
; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)*/
9 uint8_t target_system
; /*< System ID*/
10 uint8_t target_component
; /*< Component ID*/
11 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*/
12 }) mavlink_param_request_read_t
;
14 #define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20
15 #define MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN 20
16 #define MAVLINK_MSG_ID_20_LEN 20
17 #define MAVLINK_MSG_ID_20_MIN_LEN 20
19 #define MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC 214
20 #define MAVLINK_MSG_ID_20_CRC 214
22 #define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 16
24 #if MAVLINK_COMMAND_24BIT
25 #define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \
27 "PARAM_REQUEST_READ", \
29 { { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \
30 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \
31 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \
32 { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \
36 #define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \
37 "PARAM_REQUEST_READ", \
39 { { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \
40 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \
41 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \
42 { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \
48 * @brief Pack a param_request_read message
49 * @param system_id ID of this system
50 * @param component_id ID of this component (e.g. 200 for IMU)
51 * @param msg The MAVLink message to compress the data into
53 * @param target_system System ID
54 * @param target_component Component ID
55 * @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
56 * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
57 * @return length of the message in bytes (excluding serial stream start sign)
59 static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
60 uint8_t target_system
, uint8_t target_component
, const char *param_id
, int16_t param_index
)
62 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
63 char buf
[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
];
64 _mav_put_int16_t(buf
, 0, param_index
);
65 _mav_put_uint8_t(buf
, 2, target_system
);
66 _mav_put_uint8_t(buf
, 3, target_component
);
67 _mav_put_char_array(buf
, 4, param_id
, 16);
68 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);
70 mavlink_param_request_read_t packet
;
71 packet
.param_index
= param_index
;
72 packet
.target_system
= target_system
;
73 packet
.target_component
= target_component
;
74 mav_array_memcpy(packet
.param_id
, param_id
, sizeof(char)*16);
75 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);
78 msg
->msgid
= MAVLINK_MSG_ID_PARAM_REQUEST_READ
;
79 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC
);
83 * @brief Pack a param_request_read message on a channel
84 * @param system_id ID of this system
85 * @param component_id ID of this component (e.g. 200 for IMU)
86 * @param chan The MAVLink channel this message will be sent over
87 * @param msg The MAVLink message to compress the data into
88 * @param target_system System ID
89 * @param target_component Component ID
90 * @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
91 * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
92 * @return length of the message in bytes (excluding serial stream start sign)
94 static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
95 mavlink_message_t
* msg
,
96 uint8_t target_system
,uint8_t target_component
,const char *param_id
,int16_t param_index
)
98 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
99 char buf
[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
];
100 _mav_put_int16_t(buf
, 0, param_index
);
101 _mav_put_uint8_t(buf
, 2, target_system
);
102 _mav_put_uint8_t(buf
, 3, target_component
);
103 _mav_put_char_array(buf
, 4, param_id
, 16);
104 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);
106 mavlink_param_request_read_t packet
;
107 packet
.param_index
= param_index
;
108 packet
.target_system
= target_system
;
109 packet
.target_component
= target_component
;
110 mav_array_memcpy(packet
.param_id
, param_id
, sizeof(char)*16);
111 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);
114 msg
->msgid
= MAVLINK_MSG_ID_PARAM_REQUEST_READ
;
115 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC
);
119 * @brief Encode a param_request_read struct
121 * @param system_id ID of this system
122 * @param component_id ID of this component (e.g. 200 for IMU)
123 * @param msg The MAVLink message to compress the data into
124 * @param param_request_read C-struct to read the message contents from
126 static inline 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
)
128 return mavlink_msg_param_request_read_pack(system_id
, component_id
, msg
, param_request_read
->target_system
, param_request_read
->target_component
, param_request_read
->param_id
, param_request_read
->param_index
);
132 * @brief Encode a param_request_read struct on a channel
134 * @param system_id ID of this system
135 * @param component_id ID of this component (e.g. 200 for IMU)
136 * @param chan The MAVLink channel this message will be sent over
137 * @param msg The MAVLink message to compress the data into
138 * @param param_request_read C-struct to read the message contents from
140 static inline 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
)
142 return mavlink_msg_param_request_read_pack_chan(system_id
, component_id
, chan
, msg
, param_request_read
->target_system
, param_request_read
->target_component
, param_request_read
->param_id
, param_request_read
->param_index
);
146 * @brief Send a param_request_read message
147 * @param chan MAVLink channel to send the message
149 * @param target_system System ID
150 * @param target_component Component ID
151 * @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
152 * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
154 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
156 static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan
, uint8_t target_system
, uint8_t target_component
, const char *param_id
, int16_t param_index
)
158 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
159 char buf
[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
];
160 _mav_put_int16_t(buf
, 0, param_index
);
161 _mav_put_uint8_t(buf
, 2, target_system
);
162 _mav_put_uint8_t(buf
, 3, target_component
);
163 _mav_put_char_array(buf
, 4, param_id
, 16);
164 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ
, buf
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC
);
166 mavlink_param_request_read_t packet
;
167 packet
.param_index
= param_index
;
168 packet
.target_system
= target_system
;
169 packet
.target_component
= target_component
;
170 mav_array_memcpy(packet
.param_id
, param_id
, sizeof(char)*16);
171 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ
, (const char *)&packet
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC
);
176 * @brief Send a param_request_read message
177 * @param chan MAVLink channel to send the message
178 * @param struct The MAVLink struct to serialize
180 static inline void mavlink_msg_param_request_read_send_struct(mavlink_channel_t chan
, const mavlink_param_request_read_t
* param_request_read
)
182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
183 mavlink_msg_param_request_read_send(chan
, param_request_read
->target_system
, param_request_read
->target_component
, param_request_read
->param_id
, param_request_read
->param_index
);
185 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ
, (const char *)param_request_read
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC
);
189 #if MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN <= MAVLINK_MAX_PAYLOAD_LEN
191 This varient of _send() can be used to save stack space by re-using
192 memory from the receive buffer. The caller provides a
193 mavlink_message_t which is the size of a full mavlink message. This
194 is usually the receive buffer for the channel, and allows a reply to an
195 incoming message with minimum stack space usage.
197 static inline void mavlink_msg_param_request_read_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
)
199 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
200 char *buf
= (char *)msgbuf
;
201 _mav_put_int16_t(buf
, 0, param_index
);
202 _mav_put_uint8_t(buf
, 2, target_system
);
203 _mav_put_uint8_t(buf
, 3, target_component
);
204 _mav_put_char_array(buf
, 4, param_id
, 16);
205 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ
, buf
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC
);
207 mavlink_param_request_read_t
*packet
= (mavlink_param_request_read_t
*)msgbuf
;
208 packet
->param_index
= param_index
;
209 packet
->target_system
= target_system
;
210 packet
->target_component
= target_component
;
211 mav_array_memcpy(packet
->param_id
, param_id
, sizeof(char)*16);
212 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ
, (const char *)packet
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC
);
219 // MESSAGE PARAM_REQUEST_READ UNPACKING
223 * @brief Get field target_system from param_request_read message
227 static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t
* msg
)
229 return _MAV_RETURN_uint8_t(msg
, 2);
233 * @brief Get field target_component from param_request_read message
235 * @return Component ID
237 static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t
* msg
)
239 return _MAV_RETURN_uint8_t(msg
, 3);
243 * @brief Get field param_id from param_request_read message
245 * @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
247 static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t
* msg
, char *param_id
)
249 return _MAV_RETURN_char_array(msg
, param_id
, 16, 4);
253 * @brief Get field param_index from param_request_read message
255 * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
257 static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t
* msg
)
259 return _MAV_RETURN_int16_t(msg
, 0);
263 * @brief Decode a param_request_read message into a struct
265 * @param msg The message to decode
266 * @param param_request_read C-struct to decode the message contents into
268 static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t
* msg
, mavlink_param_request_read_t
* param_request_read
)
270 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
271 param_request_read
->param_index
= mavlink_msg_param_request_read_get_param_index(msg
);
272 param_request_read
->target_system
= mavlink_msg_param_request_read_get_target_system(msg
);
273 param_request_read
->target_component
= mavlink_msg_param_request_read_get_target_component(msg
);
274 mavlink_msg_param_request_read_get_param_id(msg
, param_request_read
->param_id
);
276 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
? msg
->len
: MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
;
277 memset(param_request_read
, 0, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);
278 memcpy(param_request_read
, _MAV_PAYLOAD(msg
), len
);