1 // MESSAGE PARAM_REQUEST_READ PACKING
3 #define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20
5 typedef struct __mavlink_param_request_read_t
7 int16_t param_index
; ///< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
8 uint8_t target_system
; ///< System ID
9 uint8_t target_component
; ///< Component ID
10 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
11 } mavlink_param_request_read_t
;
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) }, \
33 * @brief Pack a param_request_read message
34 * @param system_id ID of this system
35 * @param component_id ID of this component (e.g. 200 for IMU)
36 * @param msg The MAVLink message to compress the data into
38 * @param target_system System ID
39 * @param target_component Component ID
40 * @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
41 * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
42 * @return length of the message in bytes (excluding serial stream start sign)
44 static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
45 uint8_t target_system
, uint8_t target_component
, const char *param_id
, int16_t param_index
)
47 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
48 char buf
[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
];
49 _mav_put_int16_t(buf
, 0, param_index
);
50 _mav_put_uint8_t(buf
, 2, target_system
);
51 _mav_put_uint8_t(buf
, 3, target_component
);
52 _mav_put_char_array(buf
, 4, param_id
, 16);
53 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);
55 mavlink_param_request_read_t packet
;
56 packet
.param_index
= param_index
;
57 packet
.target_system
= target_system
;
58 packet
.target_component
= target_component
;
59 mav_array_memcpy(packet
.param_id
, param_id
, sizeof(char)*16);
60 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);
63 msg
->msgid
= MAVLINK_MSG_ID_PARAM_REQUEST_READ
;
65 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC
);
67 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);
72 * @brief Pack a param_request_read message on a channel
73 * @param system_id ID of this system
74 * @param component_id ID of this component (e.g. 200 for IMU)
75 * @param chan The MAVLink channel this message will be sent over
76 * @param msg The MAVLink message to compress the data into
77 * @param target_system System ID
78 * @param target_component Component ID
79 * @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
80 * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
81 * @return length of the message in bytes (excluding serial stream start sign)
83 static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
84 mavlink_message_t
* msg
,
85 uint8_t target_system
,uint8_t target_component
,const char *param_id
,int16_t param_index
)
87 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
88 char buf
[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
];
89 _mav_put_int16_t(buf
, 0, param_index
);
90 _mav_put_uint8_t(buf
, 2, target_system
);
91 _mav_put_uint8_t(buf
, 3, target_component
);
92 _mav_put_char_array(buf
, 4, param_id
, 16);
93 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);
95 mavlink_param_request_read_t packet
;
96 packet
.param_index
= param_index
;
97 packet
.target_system
= target_system
;
98 packet
.target_component
= target_component
;
99 mav_array_memcpy(packet
.param_id
, param_id
, sizeof(char)*16);
100 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);
103 msg
->msgid
= MAVLINK_MSG_ID_PARAM_REQUEST_READ
;
104 #if MAVLINK_CRC_EXTRA
105 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC
);
107 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);
112 * @brief Encode a param_request_read struct
114 * @param system_id ID of this system
115 * @param component_id ID of this component (e.g. 200 for IMU)
116 * @param msg The MAVLink message to compress the data into
117 * @param param_request_read C-struct to read the message contents from
119 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
)
121 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
);
125 * @brief Encode a param_request_read struct on a channel
127 * @param system_id ID of this system
128 * @param component_id ID of this component (e.g. 200 for IMU)
129 * @param chan The MAVLink channel this message will be sent over
130 * @param msg The MAVLink message to compress the data into
131 * @param param_request_read C-struct to read the message contents from
133 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
)
135 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
);
139 * @brief Send a param_request_read message
140 * @param chan MAVLink channel to send the message
142 * @param target_system System ID
143 * @param target_component Component ID
144 * @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
145 * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
147 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
149 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
)
151 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
152 char buf
[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
];
153 _mav_put_int16_t(buf
, 0, param_index
);
154 _mav_put_uint8_t(buf
, 2, target_system
);
155 _mav_put_uint8_t(buf
, 3, target_component
);
156 _mav_put_char_array(buf
, 4, param_id
, 16);
157 #if MAVLINK_CRC_EXTRA
158 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ
, buf
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC
);
160 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ
, buf
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);
163 mavlink_param_request_read_t packet
;
164 packet
.param_index
= param_index
;
165 packet
.target_system
= target_system
;
166 packet
.target_component
= target_component
;
167 mav_array_memcpy(packet
.param_id
, param_id
, sizeof(char)*16);
168 #if MAVLINK_CRC_EXTRA
169 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ
, (const char *)&packet
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC
);
171 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ
, (const char *)&packet
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);
176 #if MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN <= MAVLINK_MAX_PAYLOAD_LEN
178 This varient of _send() can be used to save stack space by re-using
179 memory from the receive buffer. The caller provides a
180 mavlink_message_t which is the size of a full mavlink message. This
181 is usually the receive buffer for the channel, and allows a reply to an
182 incoming message with minimum stack space usage.
184 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
)
186 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
187 char *buf
= (char *)msgbuf
;
188 _mav_put_int16_t(buf
, 0, param_index
);
189 _mav_put_uint8_t(buf
, 2, target_system
);
190 _mav_put_uint8_t(buf
, 3, target_component
);
191 _mav_put_char_array(buf
, 4, param_id
, 16);
192 #if MAVLINK_CRC_EXTRA
193 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ
, buf
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC
);
195 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ
, buf
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);
198 mavlink_param_request_read_t
*packet
= (mavlink_param_request_read_t
*)msgbuf
;
199 packet
->param_index
= param_index
;
200 packet
->target_system
= target_system
;
201 packet
->target_component
= target_component
;
202 mav_array_memcpy(packet
->param_id
, param_id
, sizeof(char)*16);
203 #if MAVLINK_CRC_EXTRA
204 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ
, (const char *)packet
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC
);
206 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_REQUEST_READ
, (const char *)packet
, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);
214 // MESSAGE PARAM_REQUEST_READ UNPACKING
218 * @brief Get field target_system from param_request_read message
222 static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t
* msg
)
224 return _MAV_RETURN_uint8_t(msg
, 2);
228 * @brief Get field target_component from param_request_read message
230 * @return Component ID
232 static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t
* msg
)
234 return _MAV_RETURN_uint8_t(msg
, 3);
238 * @brief Get field param_id from param_request_read message
240 * @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
242 static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t
* msg
, char *param_id
)
244 return _MAV_RETURN_char_array(msg
, param_id
, 16, 4);
248 * @brief Get field param_index from param_request_read message
250 * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
252 static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t
* msg
)
254 return _MAV_RETURN_int16_t(msg
, 0);
258 * @brief Decode a param_request_read message into a struct
260 * @param msg The message to decode
261 * @param param_request_read C-struct to decode the message contents into
263 static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t
* msg
, mavlink_param_request_read_t
* param_request_read
)
265 #if MAVLINK_NEED_BYTE_SWAP
266 param_request_read
->param_index
= mavlink_msg_param_request_read_get_param_index(msg
);
267 param_request_read
->target_system
= mavlink_msg_param_request_read_get_target_system(msg
);
268 param_request_read
->target_component
= mavlink_msg_param_request_read_get_target_component(msg
);
269 mavlink_msg_param_request_read_get_param_id(msg
, param_request_read
->param_id
);
271 memcpy(param_request_read
, _MAV_PAYLOAD(msg
), MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN
);