1 | // MESSAGE PARAM_VALUE PACKING
|
---|
2 |
|
---|
3 | #define MAVLINK_MSG_ID_PARAM_VALUE 22
|
---|
4 |
|
---|
5 | typedef struct MAVLINK_PACKED __mavlink_param_value_t
|
---|
6 | {
|
---|
7 | float param_value; /*< Onboard parameter value*/
|
---|
8 | uint16_t param_count; /*< Total number of onboard parameters*/
|
---|
9 | uint16_t param_index; /*< Index of this onboard parameter*/
|
---|
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_value_t;
|
---|
13 |
|
---|
14 | #define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25
|
---|
15 | #define MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN 25
|
---|
16 | #define MAVLINK_MSG_ID_22_LEN 25
|
---|
17 | #define MAVLINK_MSG_ID_22_MIN_LEN 25
|
---|
18 |
|
---|
19 | #define MAVLINK_MSG_ID_PARAM_VALUE_CRC 220
|
---|
20 | #define MAVLINK_MSG_ID_22_CRC 220
|
---|
21 |
|
---|
22 | #define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 16
|
---|
23 |
|
---|
24 | #if MAVLINK_COMMAND_24BIT
|
---|
25 | #define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \
|
---|
26 | 22, \
|
---|
27 | "PARAM_VALUE", \
|
---|
28 | 5, \
|
---|
29 | { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \
|
---|
30 | { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \
|
---|
31 | { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \
|
---|
32 | { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \
|
---|
33 | { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \
|
---|
34 | } \
|
---|
35 | }
|
---|
36 | #else
|
---|
37 | #define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \
|
---|
38 | "PARAM_VALUE", \
|
---|
39 | 5, \
|
---|
40 | { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \
|
---|
41 | { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \
|
---|
42 | { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \
|
---|
43 | { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \
|
---|
44 | { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \
|
---|
45 | } \
|
---|
46 | }
|
---|
47 | #endif
|
---|
48 |
|
---|
49 | /**
|
---|
50 | * @brief Pack a param_value message
|
---|
51 | * @param system_id ID of this system
|
---|
52 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
53 | * @param msg The MAVLink message to compress the data into
|
---|
54 | *
|
---|
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_value Onboard parameter value
|
---|
57 | * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
|
---|
58 | * @param param_count Total number of onboard parameters
|
---|
59 | * @param param_index Index of this onboard parameter
|
---|
60 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
61 | */
|
---|
62 | static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
---|
63 | const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index)
|
---|
64 | {
|
---|
65 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
66 | char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
|
---|
67 | _mav_put_float(buf, 0, param_value);
|
---|
68 | _mav_put_uint16_t(buf, 4, param_count);
|
---|
69 | _mav_put_uint16_t(buf, 6, param_index);
|
---|
70 | _mav_put_uint8_t(buf, 24, param_type);
|
---|
71 | _mav_put_char_array(buf, 8, param_id, 16);
|
---|
72 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
|
---|
73 | #else
|
---|
74 | mavlink_param_value_t packet;
|
---|
75 | packet.param_value = param_value;
|
---|
76 | packet.param_count = param_count;
|
---|
77 | packet.param_index = param_index;
|
---|
78 | packet.param_type = param_type;
|
---|
79 | mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
|
---|
80 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
|
---|
81 | #endif
|
---|
82 |
|
---|
83 | msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
|
---|
84 | return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC);
|
---|
85 | }
|
---|
86 |
|
---|
87 | /**
|
---|
88 | * @brief Pack a param_value message on a channel
|
---|
89 | * @param system_id ID of this system
|
---|
90 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
91 | * @param chan The MAVLink channel this message will be sent over
|
---|
92 | * @param msg The MAVLink message to compress the data into
|
---|
93 | * @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
|
---|
94 | * @param param_value Onboard parameter value
|
---|
95 | * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
|
---|
96 | * @param param_count Total number of onboard parameters
|
---|
97 | * @param param_index Index of this onboard parameter
|
---|
98 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
99 | */
|
---|
100 | static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
---|
101 | mavlink_message_t* msg,
|
---|
102 | const char *param_id,float param_value,uint8_t param_type,uint16_t param_count,uint16_t param_index)
|
---|
103 | {
|
---|
104 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
105 | char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
|
---|
106 | _mav_put_float(buf, 0, param_value);
|
---|
107 | _mav_put_uint16_t(buf, 4, param_count);
|
---|
108 | _mav_put_uint16_t(buf, 6, param_index);
|
---|
109 | _mav_put_uint8_t(buf, 24, param_type);
|
---|
110 | _mav_put_char_array(buf, 8, param_id, 16);
|
---|
111 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
|
---|
112 | #else
|
---|
113 | mavlink_param_value_t packet;
|
---|
114 | packet.param_value = param_value;
|
---|
115 | packet.param_count = param_count;
|
---|
116 | packet.param_index = param_index;
|
---|
117 | packet.param_type = param_type;
|
---|
118 | mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
|
---|
119 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
|
---|
120 | #endif
|
---|
121 |
|
---|
122 | msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
|
---|
123 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC);
|
---|
124 | }
|
---|
125 |
|
---|
126 | /**
|
---|
127 | * @brief Encode a param_value struct
|
---|
128 | *
|
---|
129 | * @param system_id ID of this system
|
---|
130 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
131 | * @param msg The MAVLink message to compress the data into
|
---|
132 | * @param param_value C-struct to read the message contents from
|
---|
133 | */
|
---|
134 | static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value)
|
---|
135 | {
|
---|
136 | return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index);
|
---|
137 | }
|
---|
138 |
|
---|
139 | /**
|
---|
140 | * @brief Encode a param_value struct on a channel
|
---|
141 | *
|
---|
142 | * @param system_id ID of this system
|
---|
143 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
144 | * @param chan The MAVLink channel this message will be sent over
|
---|
145 | * @param msg The MAVLink message to compress the data into
|
---|
146 | * @param param_value C-struct to read the message contents from
|
---|
147 | */
|
---|
148 | static inline uint16_t mavlink_msg_param_value_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_value_t* param_value)
|
---|
149 | {
|
---|
150 | return mavlink_msg_param_value_pack_chan(system_id, component_id, chan, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index);
|
---|
151 | }
|
---|
152 |
|
---|
153 | /**
|
---|
154 | * @brief Send a param_value message
|
---|
155 | * @param chan MAVLink channel to send the message
|
---|
156 | *
|
---|
157 | * @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
|
---|
158 | * @param param_value Onboard parameter value
|
---|
159 | * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
|
---|
160 | * @param param_count Total number of onboard parameters
|
---|
161 | * @param param_index Index of this onboard parameter
|
---|
162 | */
|
---|
163 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
---|
164 |
|
---|
165 | static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index)
|
---|
166 | {
|
---|
167 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
168 | char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
|
---|
169 | _mav_put_float(buf, 0, param_value);
|
---|
170 | _mav_put_uint16_t(buf, 4, param_count);
|
---|
171 | _mav_put_uint16_t(buf, 6, param_index);
|
---|
172 | _mav_put_uint8_t(buf, 24, param_type);
|
---|
173 | _mav_put_char_array(buf, 8, param_id, 16);
|
---|
174 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC);
|
---|
175 | #else
|
---|
176 | mavlink_param_value_t packet;
|
---|
177 | packet.param_value = param_value;
|
---|
178 | packet.param_count = param_count;
|
---|
179 | packet.param_index = param_index;
|
---|
180 | packet.param_type = param_type;
|
---|
181 | mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
|
---|
182 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC);
|
---|
183 | #endif
|
---|
184 | }
|
---|
185 |
|
---|
186 | /**
|
---|
187 | * @brief Send a param_value message
|
---|
188 | * @param chan MAVLink channel to send the message
|
---|
189 | * @param struct The MAVLink struct to serialize
|
---|
190 | */
|
---|
191 | static inline void mavlink_msg_param_value_send_struct(mavlink_channel_t chan, const mavlink_param_value_t* param_value)
|
---|
192 | {
|
---|
193 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
194 | mavlink_msg_param_value_send(chan, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index);
|
---|
195 | #else
|
---|
196 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)param_value, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC);
|
---|
197 | #endif
|
---|
198 | }
|
---|
199 |
|
---|
200 | #if MAVLINK_MSG_ID_PARAM_VALUE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
---|
201 | /*
|
---|
202 | This varient of _send() can be used to save stack space by re-using
|
---|
203 | memory from the receive buffer. The caller provides a
|
---|
204 | mavlink_message_t which is the size of a full mavlink message. This
|
---|
205 | is usually the receive buffer for the channel, and allows a reply to an
|
---|
206 | incoming message with minimum stack space usage.
|
---|
207 | */
|
---|
208 | static inline void mavlink_msg_param_value_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index)
|
---|
209 | {
|
---|
210 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
211 | char *buf = (char *)msgbuf;
|
---|
212 | _mav_put_float(buf, 0, param_value);
|
---|
213 | _mav_put_uint16_t(buf, 4, param_count);
|
---|
214 | _mav_put_uint16_t(buf, 6, param_index);
|
---|
215 | _mav_put_uint8_t(buf, 24, param_type);
|
---|
216 | _mav_put_char_array(buf, 8, param_id, 16);
|
---|
217 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC);
|
---|
218 | #else
|
---|
219 | mavlink_param_value_t *packet = (mavlink_param_value_t *)msgbuf;
|
---|
220 | packet->param_value = param_value;
|
---|
221 | packet->param_count = param_count;
|
---|
222 | packet->param_index = param_index;
|
---|
223 | packet->param_type = param_type;
|
---|
224 | mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16);
|
---|
225 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)packet, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC);
|
---|
226 | #endif
|
---|
227 | }
|
---|
228 | #endif
|
---|
229 |
|
---|
230 | #endif
|
---|
231 |
|
---|
232 | // MESSAGE PARAM_VALUE UNPACKING
|
---|
233 |
|
---|
234 |
|
---|
235 | /**
|
---|
236 | * @brief Get field param_id from param_value message
|
---|
237 | *
|
---|
238 | * @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
|
---|
239 | */
|
---|
240 | static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, char *param_id)
|
---|
241 | {
|
---|
242 | return _MAV_RETURN_char_array(msg, param_id, 16, 8);
|
---|
243 | }
|
---|
244 |
|
---|
245 | /**
|
---|
246 | * @brief Get field param_value from param_value message
|
---|
247 | *
|
---|
248 | * @return Onboard parameter value
|
---|
249 | */
|
---|
250 | static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg)
|
---|
251 | {
|
---|
252 | return _MAV_RETURN_float(msg, 0);
|
---|
253 | }
|
---|
254 |
|
---|
255 | /**
|
---|
256 | * @brief Get field param_type from param_value message
|
---|
257 | *
|
---|
258 | * @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
|
---|
259 | */
|
---|
260 | static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_message_t* msg)
|
---|
261 | {
|
---|
262 | return _MAV_RETURN_uint8_t(msg, 24);
|
---|
263 | }
|
---|
264 |
|
---|
265 | /**
|
---|
266 | * @brief Get field param_count from param_value message
|
---|
267 | *
|
---|
268 | * @return Total number of onboard parameters
|
---|
269 | */
|
---|
270 | static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg)
|
---|
271 | {
|
---|
272 | return _MAV_RETURN_uint16_t(msg, 4);
|
---|
273 | }
|
---|
274 |
|
---|
275 | /**
|
---|
276 | * @brief Get field param_index from param_value message
|
---|
277 | *
|
---|
278 | * @return Index of this onboard parameter
|
---|
279 | */
|
---|
280 | static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg)
|
---|
281 | {
|
---|
282 | return _MAV_RETURN_uint16_t(msg, 6);
|
---|
283 | }
|
---|
284 |
|
---|
285 | /**
|
---|
286 | * @brief Decode a param_value message into a struct
|
---|
287 | *
|
---|
288 | * @param msg The message to decode
|
---|
289 | * @param param_value C-struct to decode the message contents into
|
---|
290 | */
|
---|
291 | static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value)
|
---|
292 | {
|
---|
293 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
294 | param_value->param_value = mavlink_msg_param_value_get_param_value(msg);
|
---|
295 | param_value->param_count = mavlink_msg_param_value_get_param_count(msg);
|
---|
296 | param_value->param_index = mavlink_msg_param_value_get_param_index(msg);
|
---|
297 | mavlink_msg_param_value_get_param_id(msg, param_value->param_id);
|
---|
298 | param_value->param_type = mavlink_msg_param_value_get_param_type(msg);
|
---|
299 | #else
|
---|
300 | uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_VALUE_LEN? msg->len : MAVLINK_MSG_ID_PARAM_VALUE_LEN;
|
---|
301 | memset(param_value, 0, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
|
---|
302 | memcpy(param_value, _MAV_PAYLOAD(msg), len);
|
---|
303 | #endif
|
---|
304 | }
|
---|