2 // MESSAGE PARAM_SET PACKING
4 #define MAVLINK_MSG_ID_PARAM_SET 23
7 typedef struct __mavlink_param_set_t
{
8 float param_value
; /*< Onboard parameter value*/
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 uint8_t param_type
; /*< Onboard parameter type.*/
13 } mavlink_param_set_t
;
15 #define MAVLINK_MSG_ID_PARAM_SET_LEN 23
16 #define MAVLINK_MSG_ID_PARAM_SET_MIN_LEN 23
17 #define MAVLINK_MSG_ID_23_LEN 23
18 #define MAVLINK_MSG_ID_23_MIN_LEN 23
20 #define MAVLINK_MSG_ID_PARAM_SET_CRC 168
21 #define MAVLINK_MSG_ID_23_CRC 168
23 #define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 16
25 #if MAVLINK_COMMAND_24BIT
26 #define MAVLINK_MESSAGE_INFO_PARAM_SET { \
30 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \
31 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \
32 { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \
33 { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \
34 { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \
38 #define MAVLINK_MESSAGE_INFO_PARAM_SET { \
41 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \
42 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \
43 { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \
44 { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \
45 { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \
51 * @brief Pack a param_set message
52 * @param system_id ID of this system
53 * @param component_id ID of this component (e.g. 200 for IMU)
54 * @param msg The MAVLink message to compress the data into
56 * @param target_system System ID
57 * @param target_component Component ID
58 * @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
59 * @param param_value Onboard parameter value
60 * @param param_type Onboard parameter type.
61 * @return length of the message in bytes (excluding serial stream start sign)
63 static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
64 uint8_t target_system
, uint8_t target_component
, const char *param_id
, float param_value
, uint8_t param_type
)
66 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
67 char buf
[MAVLINK_MSG_ID_PARAM_SET_LEN
];
68 _mav_put_float(buf
, 0, param_value
);
69 _mav_put_uint8_t(buf
, 4, target_system
);
70 _mav_put_uint8_t(buf
, 5, target_component
);
71 _mav_put_uint8_t(buf
, 22, param_type
);
72 _mav_put_char_array(buf
, 6, param_id
, 16);
73 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_PARAM_SET_LEN
);
75 mavlink_param_set_t packet
;
76 packet
.param_value
= param_value
;
77 packet
.target_system
= target_system
;
78 packet
.target_component
= target_component
;
79 packet
.param_type
= param_type
;
80 mav_array_memcpy(packet
.param_id
, param_id
, sizeof(char)*16);
81 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_PARAM_SET_LEN
);
84 msg
->msgid
= MAVLINK_MSG_ID_PARAM_SET
;
85 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN
, MAVLINK_MSG_ID_PARAM_SET_LEN
, MAVLINK_MSG_ID_PARAM_SET_CRC
);
89 * @brief Pack a param_set message on a channel
90 * @param system_id ID of this system
91 * @param component_id ID of this component (e.g. 200 for IMU)
92 * @param chan The MAVLink channel this message will be sent over
93 * @param msg The MAVLink message to compress the data into
94 * @param target_system System ID
95 * @param target_component Component ID
96 * @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
97 * @param param_value Onboard parameter value
98 * @param param_type Onboard parameter type.
99 * @return length of the message in bytes (excluding serial stream start sign)
101 static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
102 mavlink_message_t
* msg
,
103 uint8_t target_system
,uint8_t target_component
,const char *param_id
,float param_value
,uint8_t param_type
)
105 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
106 char buf
[MAVLINK_MSG_ID_PARAM_SET_LEN
];
107 _mav_put_float(buf
, 0, param_value
);
108 _mav_put_uint8_t(buf
, 4, target_system
);
109 _mav_put_uint8_t(buf
, 5, target_component
);
110 _mav_put_uint8_t(buf
, 22, param_type
);
111 _mav_put_char_array(buf
, 6, param_id
, 16);
112 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_PARAM_SET_LEN
);
114 mavlink_param_set_t packet
;
115 packet
.param_value
= param_value
;
116 packet
.target_system
= target_system
;
117 packet
.target_component
= target_component
;
118 packet
.param_type
= param_type
;
119 mav_array_memcpy(packet
.param_id
, param_id
, sizeof(char)*16);
120 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_PARAM_SET_LEN
);
123 msg
->msgid
= MAVLINK_MSG_ID_PARAM_SET
;
124 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN
, MAVLINK_MSG_ID_PARAM_SET_LEN
, MAVLINK_MSG_ID_PARAM_SET_CRC
);
128 * @brief Encode a param_set struct
130 * @param system_id ID of this system
131 * @param component_id ID of this component (e.g. 200 for IMU)
132 * @param msg The MAVLink message to compress the data into
133 * @param param_set C-struct to read the message contents from
135 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
)
137 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
);
141 * @brief Encode a param_set struct on a channel
143 * @param system_id ID of this system
144 * @param component_id ID of this component (e.g. 200 for IMU)
145 * @param chan The MAVLink channel this message will be sent over
146 * @param msg The MAVLink message to compress the data into
147 * @param param_set C-struct to read the message contents from
149 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
)
151 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
);
155 * @brief Send a param_set message
156 * @param chan MAVLink channel to send the message
158 * @param target_system System ID
159 * @param target_component Component ID
160 * @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
161 * @param param_value Onboard parameter value
162 * @param param_type Onboard parameter type.
164 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
166 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
)
168 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
169 char buf
[MAVLINK_MSG_ID_PARAM_SET_LEN
];
170 _mav_put_float(buf
, 0, param_value
);
171 _mav_put_uint8_t(buf
, 4, target_system
);
172 _mav_put_uint8_t(buf
, 5, target_component
);
173 _mav_put_uint8_t(buf
, 22, param_type
);
174 _mav_put_char_array(buf
, 6, param_id
, 16);
175 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_SET
, buf
, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN
, MAVLINK_MSG_ID_PARAM_SET_LEN
, MAVLINK_MSG_ID_PARAM_SET_CRC
);
177 mavlink_param_set_t packet
;
178 packet
.param_value
= param_value
;
179 packet
.target_system
= target_system
;
180 packet
.target_component
= target_component
;
181 packet
.param_type
= param_type
;
182 mav_array_memcpy(packet
.param_id
, param_id
, sizeof(char)*16);
183 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_SET
, (const char *)&packet
, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN
, MAVLINK_MSG_ID_PARAM_SET_LEN
, MAVLINK_MSG_ID_PARAM_SET_CRC
);
188 * @brief Send a param_set message
189 * @param chan MAVLink channel to send the message
190 * @param struct The MAVLink struct to serialize
192 static inline void mavlink_msg_param_set_send_struct(mavlink_channel_t chan
, const mavlink_param_set_t
* param_set
)
194 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
195 mavlink_msg_param_set_send(chan
, param_set
->target_system
, param_set
->target_component
, param_set
->param_id
, param_set
->param_value
, param_set
->param_type
);
197 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_SET
, (const char *)param_set
, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN
, MAVLINK_MSG_ID_PARAM_SET_LEN
, MAVLINK_MSG_ID_PARAM_SET_CRC
);
201 #if MAVLINK_MSG_ID_PARAM_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
203 This varient of _send() can be used to save stack space by re-using
204 memory from the receive buffer. The caller provides a
205 mavlink_message_t which is the size of a full mavlink message. This
206 is usually the receive buffer for the channel, and allows a reply to an
207 incoming message with minimum stack space usage.
209 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
)
211 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
212 char *buf
= (char *)msgbuf
;
213 _mav_put_float(buf
, 0, param_value
);
214 _mav_put_uint8_t(buf
, 4, target_system
);
215 _mav_put_uint8_t(buf
, 5, target_component
);
216 _mav_put_uint8_t(buf
, 22, param_type
);
217 _mav_put_char_array(buf
, 6, param_id
, 16);
218 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_SET
, buf
, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN
, MAVLINK_MSG_ID_PARAM_SET_LEN
, MAVLINK_MSG_ID_PARAM_SET_CRC
);
220 mavlink_param_set_t
*packet
= (mavlink_param_set_t
*)msgbuf
;
221 packet
->param_value
= param_value
;
222 packet
->target_system
= target_system
;
223 packet
->target_component
= target_component
;
224 packet
->param_type
= param_type
;
225 mav_array_memcpy(packet
->param_id
, param_id
, sizeof(char)*16);
226 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PARAM_SET
, (const char *)packet
, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN
, MAVLINK_MSG_ID_PARAM_SET_LEN
, MAVLINK_MSG_ID_PARAM_SET_CRC
);
233 // MESSAGE PARAM_SET UNPACKING
237 * @brief Get field target_system from param_set message
241 static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t
* msg
)
243 return _MAV_RETURN_uint8_t(msg
, 4);
247 * @brief Get field target_component from param_set message
249 * @return Component ID
251 static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t
* msg
)
253 return _MAV_RETURN_uint8_t(msg
, 5);
257 * @brief Get field param_id from param_set message
259 * @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
261 static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t
* msg
, char *param_id
)
263 return _MAV_RETURN_char_array(msg
, param_id
, 16, 6);
267 * @brief Get field param_value from param_set message
269 * @return Onboard parameter value
271 static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t
* msg
)
273 return _MAV_RETURN_float(msg
, 0);
277 * @brief Get field param_type from param_set message
279 * @return Onboard parameter type.
281 static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t
* msg
)
283 return _MAV_RETURN_uint8_t(msg
, 22);
287 * @brief Decode a param_set message into a struct
289 * @param msg The message to decode
290 * @param param_set C-struct to decode the message contents into
292 static inline void mavlink_msg_param_set_decode(const mavlink_message_t
* msg
, mavlink_param_set_t
* param_set
)
294 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
295 param_set
->param_value
= mavlink_msg_param_set_get_param_value(msg
);
296 param_set
->target_system
= mavlink_msg_param_set_get_target_system(msg
);
297 param_set
->target_component
= mavlink_msg_param_set_get_target_component(msg
);
298 mavlink_msg_param_set_get_param_id(msg
, param_set
->param_id
);
299 param_set
->param_type
= mavlink_msg_param_set_get_param_type(msg
);
301 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_PARAM_SET_LEN
? msg
->len
: MAVLINK_MSG_ID_PARAM_SET_LEN
;
302 memset(param_set
, 0, MAVLINK_MSG_ID_PARAM_SET_LEN
);
303 memcpy(param_set
, _MAV_PAYLOAD(msg
), len
);