1 // MESSAGE PARAM_SET PACKING
3 #define MAVLINK_MSG_ID_PARAM_SET 23
5 typedef struct __mavlink_param_set_t
7 float param_value
; ///< Onboard parameter value
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 uint8_t param_type
; ///< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
12 } mavlink_param_set_t
;
14 #define MAVLINK_MSG_ID_PARAM_SET_LEN 23
15 #define MAVLINK_MSG_ID_23_LEN 23
17 #define MAVLINK_MSG_ID_PARAM_SET_CRC 168
18 #define MAVLINK_MSG_ID_23_CRC 168
20 #define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 16
22 #define MAVLINK_MESSAGE_INFO_PARAM_SET { \
25 { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \
26 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \
27 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \
28 { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \
29 { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \
35 * @brief Pack a param_set message
36 * @param system_id ID of this system
37 * @param component_id ID of this component (e.g. 200 for IMU)
38 * @param msg The MAVLink message to compress the data into
40 * @param target_system System ID
41 * @param target_component Component ID
42 * @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
43 * @param param_value Onboard parameter value
44 * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
45 * @return length of the message in bytes (excluding serial stream start sign)
47 static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
48 uint8_t target_system
, uint8_t target_component
, const char *param_id
, float param_value
, uint8_t param_type
)
50 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
51 char buf
[MAVLINK_MSG_ID_PARAM_SET_LEN
];
52 _mav_put_float(buf
, 0, param_value
);
53 _mav_put_uint8_t(buf
, 4, target_system
);
54 _mav_put_uint8_t(buf
, 5, target_component
);
55 _mav_put_uint8_t(buf
, 22, param_type
);
56 _mav_put_char_array(buf
, 6, param_id
, 16);
57 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_PARAM_SET_LEN
);
59 mavlink_param_set_t packet
;
60 packet
.param_value
= param_value
;
61 packet
.target_system
= target_system
;
62 packet
.target_component
= target_component
;
63 packet
.param_type
= param_type
;
64 mav_array_memcpy(packet
.param_id
, param_id
, sizeof(char)*16);
65 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_PARAM_SET_LEN
);
68 msg
->msgid
= MAVLINK_MSG_ID_PARAM_SET
;
70 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_PARAM_SET_LEN
, MAVLINK_MSG_ID_PARAM_SET_CRC
);
72 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_PARAM_SET_LEN
);
77 * @brief Pack a param_set message on a channel
78 * @param system_id ID of this system
79 * @param component_id ID of this component (e.g. 200 for IMU)
80 * @param chan The MAVLink channel this message will be sent over
81 * @param msg The MAVLink message to compress the data into
82 * @param target_system System ID
83 * @param target_component Component ID
84 * @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
85 * @param param_value Onboard parameter value
86 * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
87 * @return length of the message in bytes (excluding serial stream start sign)
89 static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
90 mavlink_message_t
* msg
,
91 uint8_t target_system
,uint8_t target_component
,const char *param_id
,float param_value
,uint8_t param_type
)
93 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
94 char buf
[MAVLINK_MSG_ID_PARAM_SET_LEN
];
95 _mav_put_float(buf
, 0, param_value
);
96 _mav_put_uint8_t(buf
, 4, target_system
);
97 _mav_put_uint8_t(buf
, 5, target_component
);
98 _mav_put_uint8_t(buf
, 22, param_type
);
99 _mav_put_char_array(buf
, 6, param_id
, 16);
100 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_PARAM_SET_LEN
);
102 mavlink_param_set_t packet
;
103 packet
.param_value
= param_value
;
104 packet
.target_system
= target_system
;
105 packet
.target_component
= target_component
;
106 packet
.param_type
= param_type
;
107 mav_array_memcpy(packet
.param_id
, param_id
, sizeof(char)*16);
108 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_PARAM_SET_LEN
);
111 msg
->msgid
= MAVLINK_MSG_ID_PARAM_SET
;
112 #if MAVLINK_CRC_EXTRA
113 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_PARAM_SET_LEN
, MAVLINK_MSG_ID_PARAM_SET_CRC
);
115 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_PARAM_SET_LEN
);
120 * @brief Encode a param_set struct
122 * @param system_id ID of this system
123 * @param component_id ID of this component (e.g. 200 for IMU)
124 * @param msg The MAVLink message to compress the data into
125 * @param param_set C-struct to read the message contents from
127 static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_param_set_t
* param_set
)
129 return mavlink_msg_param_set_pack(system_id
, component_id
, msg
, param_set
->target_system
, param_set
->target_component
, param_set
->param_id
, param_set
->param_value
, param_set
->param_type
);
133 * @brief Encode a param_set struct on a channel
135 * @param system_id ID of this system
136 * @param component_id ID of this component (e.g. 200 for IMU)
137 * @param chan The MAVLink channel this message will be sent over
138 * @param msg The MAVLink message to compress the data into
139 * @param param_set C-struct to read the message contents from
141 static inline uint16_t mavlink_msg_param_set_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_param_set_t
* param_set
)
143 return mavlink_msg_param_set_pack_chan(system_id
, component_id
, chan
, msg
, param_set
->target_system
, param_set
->target_component
, param_set
->param_id
, param_set
->param_value
, param_set
->param_type
);
147 * @brief Send a param_set message
148 * @param chan MAVLink channel to send the message
150 * @param target_system System ID
151 * @param target_component Component ID
152 * @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
153 * @param param_value Onboard parameter value
154 * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
156 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
158 static inline void mavlink_msg_param_set_send(mavlink_channel_t chan
, uint8_t target_system
, uint8_t target_component
, const char *param_id
, float param_value
, uint8_t param_type
)
160 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
161 char buf
[MAVLINK_MSG_ID_PARAM_SET_LEN
];
162 _mav_put_float(buf
, 0, param_value
);
163 _mav_put_uint8_t(buf
, 4, target_system
);
164 _mav_put_uint8_t(buf
, 5, target_component
);
165 _mav_put_uint8_t(buf
, 22, param_type
);
166 _mav_put_char_array(buf
, 6, param_id
, 16);
167 #if MAVLINK_CRC_EXTRA
168 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_SET
, buf
, MAVLINK_MSG_ID_PARAM_SET_LEN
, MAVLINK_MSG_ID_PARAM_SET_CRC
);
170 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_SET
, buf
, MAVLINK_MSG_ID_PARAM_SET_LEN
);
173 mavlink_param_set_t packet
;
174 packet
.param_value
= param_value
;
175 packet
.target_system
= target_system
;
176 packet
.target_component
= target_component
;
177 packet
.param_type
= param_type
;
178 mav_array_memcpy(packet
.param_id
, param_id
, sizeof(char)*16);
179 #if MAVLINK_CRC_EXTRA
180 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_SET
, (const char *)&packet
, MAVLINK_MSG_ID_PARAM_SET_LEN
, MAVLINK_MSG_ID_PARAM_SET_CRC
);
182 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_SET
, (const char *)&packet
, MAVLINK_MSG_ID_PARAM_SET_LEN
);
187 #if MAVLINK_MSG_ID_PARAM_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
189 This varient of _send() can be used to save stack space by re-using
190 memory from the receive buffer. The caller provides a
191 mavlink_message_t which is the size of a full mavlink message. This
192 is usually the receive buffer for the channel, and allows a reply to an
193 incoming message with minimum stack space usage.
195 static inline void mavlink_msg_param_set_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint8_t target_system
, uint8_t target_component
, const char *param_id
, float param_value
, uint8_t param_type
)
197 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
198 char *buf
= (char *)msgbuf
;
199 _mav_put_float(buf
, 0, param_value
);
200 _mav_put_uint8_t(buf
, 4, target_system
);
201 _mav_put_uint8_t(buf
, 5, target_component
);
202 _mav_put_uint8_t(buf
, 22, param_type
);
203 _mav_put_char_array(buf
, 6, param_id
, 16);
204 #if MAVLINK_CRC_EXTRA
205 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_SET
, buf
, MAVLINK_MSG_ID_PARAM_SET_LEN
, MAVLINK_MSG_ID_PARAM_SET_CRC
);
207 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_SET
, buf
, MAVLINK_MSG_ID_PARAM_SET_LEN
);
210 mavlink_param_set_t
*packet
= (mavlink_param_set_t
*)msgbuf
;
211 packet
->param_value
= param_value
;
212 packet
->target_system
= target_system
;
213 packet
->target_component
= target_component
;
214 packet
->param_type
= param_type
;
215 mav_array_memcpy(packet
->param_id
, param_id
, sizeof(char)*16);
216 #if MAVLINK_CRC_EXTRA
217 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_SET
, (const char *)packet
, MAVLINK_MSG_ID_PARAM_SET_LEN
, MAVLINK_MSG_ID_PARAM_SET_CRC
);
219 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_SET
, (const char *)packet
, MAVLINK_MSG_ID_PARAM_SET_LEN
);
227 // MESSAGE PARAM_SET UNPACKING
231 * @brief Get field target_system from param_set message
235 static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t
* msg
)
237 return _MAV_RETURN_uint8_t(msg
, 4);
241 * @brief Get field target_component from param_set message
243 * @return Component ID
245 static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t
* msg
)
247 return _MAV_RETURN_uint8_t(msg
, 5);
251 * @brief Get field param_id from param_set message
253 * @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
255 static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t
* msg
, char *param_id
)
257 return _MAV_RETURN_char_array(msg
, param_id
, 16, 6);
261 * @brief Get field param_value from param_set message
263 * @return Onboard parameter value
265 static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t
* msg
)
267 return _MAV_RETURN_float(msg
, 0);
271 * @brief Get field param_type from param_set message
273 * @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
275 static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t
* msg
)
277 return _MAV_RETURN_uint8_t(msg
, 22);
281 * @brief Decode a param_set message into a struct
283 * @param msg The message to decode
284 * @param param_set C-struct to decode the message contents into
286 static inline void mavlink_msg_param_set_decode(const mavlink_message_t
* msg
, mavlink_param_set_t
* param_set
)
288 #if MAVLINK_NEED_BYTE_SWAP
289 param_set
->param_value
= mavlink_msg_param_set_get_param_value(msg
);
290 param_set
->target_system
= mavlink_msg_param_set_get_target_system(msg
);
291 param_set
->target_component
= mavlink_msg_param_set_get_target_component(msg
);
292 mavlink_msg_param_set_get_param_id(msg
, param_set
->param_id
);
293 param_set
->param_type
= mavlink_msg_param_set_get_param_type(msg
);
295 memcpy(param_set
, _MAV_PAYLOAD(msg
), MAVLINK_MSG_ID_PARAM_SET_LEN
);