1 | // MESSAGE COMMAND_LONG PACKING |
---|
2 | |
---|
3 | #define MAVLINK_MSG_ID_COMMAND_LONG 76 |
---|
4 | |
---|
5 | MAVPACKED( |
---|
6 | typedef struct __mavlink_command_long_t { |
---|
7 | float param1; /*< Parameter 1, as defined by MAV_CMD enum.*/ |
---|
8 | float param2; /*< Parameter 2, as defined by MAV_CMD enum.*/ |
---|
9 | float param3; /*< Parameter 3, as defined by MAV_CMD enum.*/ |
---|
10 | float param4; /*< Parameter 4, as defined by MAV_CMD enum.*/ |
---|
11 | float param5; /*< Parameter 5, as defined by MAV_CMD enum.*/ |
---|
12 | float param6; /*< Parameter 6, as defined by MAV_CMD enum.*/ |
---|
13 | float param7; /*< Parameter 7, as defined by MAV_CMD enum.*/ |
---|
14 | uint16_t command; /*< Command ID, as defined by MAV_CMD enum.*/ |
---|
15 | uint8_t target_system; /*< System which should execute the command*/ |
---|
16 | uint8_t target_component; /*< Component which should execute the command, 0 for all components*/ |
---|
17 | uint8_t confirmation; /*< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)*/ |
---|
18 | }) mavlink_command_long_t; |
---|
19 | |
---|
20 | #define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33 |
---|
21 | #define MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN 33 |
---|
22 | #define MAVLINK_MSG_ID_76_LEN 33 |
---|
23 | #define MAVLINK_MSG_ID_76_MIN_LEN 33 |
---|
24 | |
---|
25 | #define MAVLINK_MSG_ID_COMMAND_LONG_CRC 152 |
---|
26 | #define MAVLINK_MSG_ID_76_CRC 152 |
---|
27 | |
---|
28 | |
---|
29 | |
---|
30 | #if MAVLINK_COMMAND_24BIT |
---|
31 | #define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \ |
---|
32 | 76, \ |
---|
33 | "COMMAND_LONG", \ |
---|
34 | 11, \ |
---|
35 | { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ |
---|
36 | { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \ |
---|
37 | { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \ |
---|
38 | { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \ |
---|
39 | { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \ |
---|
40 | { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \ |
---|
41 | { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \ |
---|
42 | { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ |
---|
43 | { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ |
---|
44 | { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ |
---|
45 | { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ |
---|
46 | } \ |
---|
47 | } |
---|
48 | #else |
---|
49 | #define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \ |
---|
50 | "COMMAND_LONG", \ |
---|
51 | 11, \ |
---|
52 | { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ |
---|
53 | { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \ |
---|
54 | { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \ |
---|
55 | { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \ |
---|
56 | { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \ |
---|
57 | { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \ |
---|
58 | { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \ |
---|
59 | { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ |
---|
60 | { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ |
---|
61 | { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ |
---|
62 | { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ |
---|
63 | } \ |
---|
64 | } |
---|
65 | #endif |
---|
66 | |
---|
67 | /** |
---|
68 | * @brief Pack a command_long message |
---|
69 | * @param system_id ID of this system |
---|
70 | * @param component_id ID of this component (e.g. 200 for IMU) |
---|
71 | * @param msg The MAVLink message to compress the data into |
---|
72 | * |
---|
73 | * @param target_system System which should execute the command |
---|
74 | * @param target_component Component which should execute the command, 0 for all components |
---|
75 | * @param command Command ID, as defined by MAV_CMD enum. |
---|
76 | * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) |
---|
77 | * @param param1 Parameter 1, as defined by MAV_CMD enum. |
---|
78 | * @param param2 Parameter 2, as defined by MAV_CMD enum. |
---|
79 | * @param param3 Parameter 3, as defined by MAV_CMD enum. |
---|
80 | * @param param4 Parameter 4, as defined by MAV_CMD enum. |
---|
81 | * @param param5 Parameter 5, as defined by MAV_CMD enum. |
---|
82 | * @param param6 Parameter 6, as defined by MAV_CMD enum. |
---|
83 | * @param param7 Parameter 7, as defined by MAV_CMD enum. |
---|
84 | * @return length of the message in bytes (excluding serial stream start sign) |
---|
85 | */ |
---|
86 | static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, |
---|
87 | uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) |
---|
88 | { |
---|
89 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
90 | char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; |
---|
91 | _mav_put_float(buf, 0, param1); |
---|
92 | _mav_put_float(buf, 4, param2); |
---|
93 | _mav_put_float(buf, 8, param3); |
---|
94 | _mav_put_float(buf, 12, param4); |
---|
95 | _mav_put_float(buf, 16, param5); |
---|
96 | _mav_put_float(buf, 20, param6); |
---|
97 | _mav_put_float(buf, 24, param7); |
---|
98 | _mav_put_uint16_t(buf, 28, command); |
---|
99 | _mav_put_uint8_t(buf, 30, target_system); |
---|
100 | _mav_put_uint8_t(buf, 31, target_component); |
---|
101 | _mav_put_uint8_t(buf, 32, confirmation); |
---|
102 | |
---|
103 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); |
---|
104 | #else |
---|
105 | mavlink_command_long_t packet; |
---|
106 | packet.param1 = param1; |
---|
107 | packet.param2 = param2; |
---|
108 | packet.param3 = param3; |
---|
109 | packet.param4 = param4; |
---|
110 | packet.param5 = param5; |
---|
111 | packet.param6 = param6; |
---|
112 | packet.param7 = param7; |
---|
113 | packet.command = command; |
---|
114 | packet.target_system = target_system; |
---|
115 | packet.target_component = target_component; |
---|
116 | packet.confirmation = confirmation; |
---|
117 | |
---|
118 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); |
---|
119 | #endif |
---|
120 | |
---|
121 | msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; |
---|
122 | return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); |
---|
123 | } |
---|
124 | |
---|
125 | /** |
---|
126 | * @brief Pack a command_long message 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 target_system System which should execute the command |
---|
132 | * @param target_component Component which should execute the command, 0 for all components |
---|
133 | * @param command Command ID, as defined by MAV_CMD enum. |
---|
134 | * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) |
---|
135 | * @param param1 Parameter 1, as defined by MAV_CMD enum. |
---|
136 | * @param param2 Parameter 2, as defined by MAV_CMD enum. |
---|
137 | * @param param3 Parameter 3, as defined by MAV_CMD enum. |
---|
138 | * @param param4 Parameter 4, as defined by MAV_CMD enum. |
---|
139 | * @param param5 Parameter 5, as defined by MAV_CMD enum. |
---|
140 | * @param param6 Parameter 6, as defined by MAV_CMD enum. |
---|
141 | * @param param7 Parameter 7, as defined by MAV_CMD enum. |
---|
142 | * @return length of the message in bytes (excluding serial stream start sign) |
---|
143 | */ |
---|
144 | static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, |
---|
145 | mavlink_message_t* msg, |
---|
146 | uint8_t target_system,uint8_t target_component,uint16_t command,uint8_t confirmation,float param1,float param2,float param3,float param4,float param5,float param6,float param7) |
---|
147 | { |
---|
148 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
149 | char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; |
---|
150 | _mav_put_float(buf, 0, param1); |
---|
151 | _mav_put_float(buf, 4, param2); |
---|
152 | _mav_put_float(buf, 8, param3); |
---|
153 | _mav_put_float(buf, 12, param4); |
---|
154 | _mav_put_float(buf, 16, param5); |
---|
155 | _mav_put_float(buf, 20, param6); |
---|
156 | _mav_put_float(buf, 24, param7); |
---|
157 | _mav_put_uint16_t(buf, 28, command); |
---|
158 | _mav_put_uint8_t(buf, 30, target_system); |
---|
159 | _mav_put_uint8_t(buf, 31, target_component); |
---|
160 | _mav_put_uint8_t(buf, 32, confirmation); |
---|
161 | |
---|
162 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); |
---|
163 | #else |
---|
164 | mavlink_command_long_t packet; |
---|
165 | packet.param1 = param1; |
---|
166 | packet.param2 = param2; |
---|
167 | packet.param3 = param3; |
---|
168 | packet.param4 = param4; |
---|
169 | packet.param5 = param5; |
---|
170 | packet.param6 = param6; |
---|
171 | packet.param7 = param7; |
---|
172 | packet.command = command; |
---|
173 | packet.target_system = target_system; |
---|
174 | packet.target_component = target_component; |
---|
175 | packet.confirmation = confirmation; |
---|
176 | |
---|
177 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); |
---|
178 | #endif |
---|
179 | |
---|
180 | msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; |
---|
181 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); |
---|
182 | } |
---|
183 | |
---|
184 | /** |
---|
185 | * @brief Encode a command_long struct |
---|
186 | * |
---|
187 | * @param system_id ID of this system |
---|
188 | * @param component_id ID of this component (e.g. 200 for IMU) |
---|
189 | * @param msg The MAVLink message to compress the data into |
---|
190 | * @param command_long C-struct to read the message contents from |
---|
191 | */ |
---|
192 | static inline uint16_t mavlink_msg_command_long_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_long_t* command_long) |
---|
193 | { |
---|
194 | return mavlink_msg_command_long_pack(system_id, component_id, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); |
---|
195 | } |
---|
196 | |
---|
197 | /** |
---|
198 | * @brief Encode a command_long struct on a channel |
---|
199 | * |
---|
200 | * @param system_id ID of this system |
---|
201 | * @param component_id ID of this component (e.g. 200 for IMU) |
---|
202 | * @param chan The MAVLink channel this message will be sent over |
---|
203 | * @param msg The MAVLink message to compress the data into |
---|
204 | * @param command_long C-struct to read the message contents from |
---|
205 | */ |
---|
206 | static inline uint16_t mavlink_msg_command_long_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_long_t* command_long) |
---|
207 | { |
---|
208 | return mavlink_msg_command_long_pack_chan(system_id, component_id, chan, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); |
---|
209 | } |
---|
210 | |
---|
211 | /** |
---|
212 | * @brief Send a command_long message |
---|
213 | * @param chan MAVLink channel to send the message |
---|
214 | * |
---|
215 | * @param target_system System which should execute the command |
---|
216 | * @param target_component Component which should execute the command, 0 for all components |
---|
217 | * @param command Command ID, as defined by MAV_CMD enum. |
---|
218 | * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) |
---|
219 | * @param param1 Parameter 1, as defined by MAV_CMD enum. |
---|
220 | * @param param2 Parameter 2, as defined by MAV_CMD enum. |
---|
221 | * @param param3 Parameter 3, as defined by MAV_CMD enum. |
---|
222 | * @param param4 Parameter 4, as defined by MAV_CMD enum. |
---|
223 | * @param param5 Parameter 5, as defined by MAV_CMD enum. |
---|
224 | * @param param6 Parameter 6, as defined by MAV_CMD enum. |
---|
225 | * @param param7 Parameter 7, as defined by MAV_CMD enum. |
---|
226 | */ |
---|
227 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
---|
228 | |
---|
229 | static inline void mavlink_msg_command_long_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) |
---|
230 | { |
---|
231 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
232 | char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; |
---|
233 | _mav_put_float(buf, 0, param1); |
---|
234 | _mav_put_float(buf, 4, param2); |
---|
235 | _mav_put_float(buf, 8, param3); |
---|
236 | _mav_put_float(buf, 12, param4); |
---|
237 | _mav_put_float(buf, 16, param5); |
---|
238 | _mav_put_float(buf, 20, param6); |
---|
239 | _mav_put_float(buf, 24, param7); |
---|
240 | _mav_put_uint16_t(buf, 28, command); |
---|
241 | _mav_put_uint8_t(buf, 30, target_system); |
---|
242 | _mav_put_uint8_t(buf, 31, target_component); |
---|
243 | _mav_put_uint8_t(buf, 32, confirmation); |
---|
244 | |
---|
245 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); |
---|
246 | #else |
---|
247 | mavlink_command_long_t packet; |
---|
248 | packet.param1 = param1; |
---|
249 | packet.param2 = param2; |
---|
250 | packet.param3 = param3; |
---|
251 | packet.param4 = param4; |
---|
252 | packet.param5 = param5; |
---|
253 | packet.param6 = param6; |
---|
254 | packet.param7 = param7; |
---|
255 | packet.command = command; |
---|
256 | packet.target_system = target_system; |
---|
257 | packet.target_component = target_component; |
---|
258 | packet.confirmation = confirmation; |
---|
259 | |
---|
260 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); |
---|
261 | #endif |
---|
262 | } |
---|
263 | |
---|
264 | /** |
---|
265 | * @brief Send a command_long message |
---|
266 | * @param chan MAVLink channel to send the message |
---|
267 | * @param struct The MAVLink struct to serialize |
---|
268 | */ |
---|
269 | static inline void mavlink_msg_command_long_send_struct(mavlink_channel_t chan, const mavlink_command_long_t* command_long) |
---|
270 | { |
---|
271 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
272 | mavlink_msg_command_long_send(chan, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); |
---|
273 | #else |
---|
274 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)command_long, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); |
---|
275 | #endif |
---|
276 | } |
---|
277 | |
---|
278 | #if MAVLINK_MSG_ID_COMMAND_LONG_LEN <= MAVLINK_MAX_PAYLOAD_LEN |
---|
279 | /* |
---|
280 | This varient of _send() can be used to save stack space by re-using |
---|
281 | memory from the receive buffer. The caller provides a |
---|
282 | mavlink_message_t which is the size of a full mavlink message. This |
---|
283 | is usually the receive buffer for the channel, and allows a reply to an |
---|
284 | incoming message with minimum stack space usage. |
---|
285 | */ |
---|
286 | static inline void mavlink_msg_command_long_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) |
---|
287 | { |
---|
288 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
289 | char *buf = (char *)msgbuf; |
---|
290 | _mav_put_float(buf, 0, param1); |
---|
291 | _mav_put_float(buf, 4, param2); |
---|
292 | _mav_put_float(buf, 8, param3); |
---|
293 | _mav_put_float(buf, 12, param4); |
---|
294 | _mav_put_float(buf, 16, param5); |
---|
295 | _mav_put_float(buf, 20, param6); |
---|
296 | _mav_put_float(buf, 24, param7); |
---|
297 | _mav_put_uint16_t(buf, 28, command); |
---|
298 | _mav_put_uint8_t(buf, 30, target_system); |
---|
299 | _mav_put_uint8_t(buf, 31, target_component); |
---|
300 | _mav_put_uint8_t(buf, 32, confirmation); |
---|
301 | |
---|
302 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); |
---|
303 | #else |
---|
304 | mavlink_command_long_t *packet = (mavlink_command_long_t *)msgbuf; |
---|
305 | packet->param1 = param1; |
---|
306 | packet->param2 = param2; |
---|
307 | packet->param3 = param3; |
---|
308 | packet->param4 = param4; |
---|
309 | packet->param5 = param5; |
---|
310 | packet->param6 = param6; |
---|
311 | packet->param7 = param7; |
---|
312 | packet->command = command; |
---|
313 | packet->target_system = target_system; |
---|
314 | packet->target_component = target_component; |
---|
315 | packet->confirmation = confirmation; |
---|
316 | |
---|
317 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); |
---|
318 | #endif |
---|
319 | } |
---|
320 | #endif |
---|
321 | |
---|
322 | #endif |
---|
323 | |
---|
324 | // MESSAGE COMMAND_LONG UNPACKING |
---|
325 | |
---|
326 | |
---|
327 | /** |
---|
328 | * @brief Get field target_system from command_long message |
---|
329 | * |
---|
330 | * @return System which should execute the command |
---|
331 | */ |
---|
332 | static inline uint8_t mavlink_msg_command_long_get_target_system(const mavlink_message_t* msg) |
---|
333 | { |
---|
334 | return _MAV_RETURN_uint8_t(msg, 30); |
---|
335 | } |
---|
336 | |
---|
337 | /** |
---|
338 | * @brief Get field target_component from command_long message |
---|
339 | * |
---|
340 | * @return Component which should execute the command, 0 for all components |
---|
341 | */ |
---|
342 | static inline uint8_t mavlink_msg_command_long_get_target_component(const mavlink_message_t* msg) |
---|
343 | { |
---|
344 | return _MAV_RETURN_uint8_t(msg, 31); |
---|
345 | } |
---|
346 | |
---|
347 | /** |
---|
348 | * @brief Get field command from command_long message |
---|
349 | * |
---|
350 | * @return Command ID, as defined by MAV_CMD enum. |
---|
351 | */ |
---|
352 | static inline uint16_t mavlink_msg_command_long_get_command(const mavlink_message_t* msg) |
---|
353 | { |
---|
354 | return _MAV_RETURN_uint16_t(msg, 28); |
---|
355 | } |
---|
356 | |
---|
357 | /** |
---|
358 | * @brief Get field confirmation from command_long message |
---|
359 | * |
---|
360 | * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) |
---|
361 | */ |
---|
362 | static inline uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_message_t* msg) |
---|
363 | { |
---|
364 | return _MAV_RETURN_uint8_t(msg, 32); |
---|
365 | } |
---|
366 | |
---|
367 | /** |
---|
368 | * @brief Get field param1 from command_long message |
---|
369 | * |
---|
370 | * @return Parameter 1, as defined by MAV_CMD enum. |
---|
371 | */ |
---|
372 | static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t* msg) |
---|
373 | { |
---|
374 | return _MAV_RETURN_float(msg, 0); |
---|
375 | } |
---|
376 | |
---|
377 | /** |
---|
378 | * @brief Get field param2 from command_long message |
---|
379 | * |
---|
380 | * @return Parameter 2, as defined by MAV_CMD enum. |
---|
381 | */ |
---|
382 | static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t* msg) |
---|
383 | { |
---|
384 | return _MAV_RETURN_float(msg, 4); |
---|
385 | } |
---|
386 | |
---|
387 | /** |
---|
388 | * @brief Get field param3 from command_long message |
---|
389 | * |
---|
390 | * @return Parameter 3, as defined by MAV_CMD enum. |
---|
391 | */ |
---|
392 | static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t* msg) |
---|
393 | { |
---|
394 | return _MAV_RETURN_float(msg, 8); |
---|
395 | } |
---|
396 | |
---|
397 | /** |
---|
398 | * @brief Get field param4 from command_long message |
---|
399 | * |
---|
400 | * @return Parameter 4, as defined by MAV_CMD enum. |
---|
401 | */ |
---|
402 | static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t* msg) |
---|
403 | { |
---|
404 | return _MAV_RETURN_float(msg, 12); |
---|
405 | } |
---|
406 | |
---|
407 | /** |
---|
408 | * @brief Get field param5 from command_long message |
---|
409 | * |
---|
410 | * @return Parameter 5, as defined by MAV_CMD enum. |
---|
411 | */ |
---|
412 | static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t* msg) |
---|
413 | { |
---|
414 | return _MAV_RETURN_float(msg, 16); |
---|
415 | } |
---|
416 | |
---|
417 | /** |
---|
418 | * @brief Get field param6 from command_long message |
---|
419 | * |
---|
420 | * @return Parameter 6, as defined by MAV_CMD enum. |
---|
421 | */ |
---|
422 | static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t* msg) |
---|
423 | { |
---|
424 | return _MAV_RETURN_float(msg, 20); |
---|
425 | } |
---|
426 | |
---|
427 | /** |
---|
428 | * @brief Get field param7 from command_long message |
---|
429 | * |
---|
430 | * @return Parameter 7, as defined by MAV_CMD enum. |
---|
431 | */ |
---|
432 | static inline float mavlink_msg_command_long_get_param7(const mavlink_message_t* msg) |
---|
433 | { |
---|
434 | return _MAV_RETURN_float(msg, 24); |
---|
435 | } |
---|
436 | |
---|
437 | /** |
---|
438 | * @brief Decode a command_long message into a struct |
---|
439 | * |
---|
440 | * @param msg The message to decode |
---|
441 | * @param command_long C-struct to decode the message contents into |
---|
442 | */ |
---|
443 | static inline void mavlink_msg_command_long_decode(const mavlink_message_t* msg, mavlink_command_long_t* command_long) |
---|
444 | { |
---|
445 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
446 | command_long->param1 = mavlink_msg_command_long_get_param1(msg); |
---|
447 | command_long->param2 = mavlink_msg_command_long_get_param2(msg); |
---|
448 | command_long->param3 = mavlink_msg_command_long_get_param3(msg); |
---|
449 | command_long->param4 = mavlink_msg_command_long_get_param4(msg); |
---|
450 | command_long->param5 = mavlink_msg_command_long_get_param5(msg); |
---|
451 | command_long->param6 = mavlink_msg_command_long_get_param6(msg); |
---|
452 | command_long->param7 = mavlink_msg_command_long_get_param7(msg); |
---|
453 | command_long->command = mavlink_msg_command_long_get_command(msg); |
---|
454 | command_long->target_system = mavlink_msg_command_long_get_target_system(msg); |
---|
455 | command_long->target_component = mavlink_msg_command_long_get_target_component(msg); |
---|
456 | command_long->confirmation = mavlink_msg_command_long_get_confirmation(msg); |
---|
457 | #else |
---|
458 | uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_LONG_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_LONG_LEN; |
---|
459 | memset(command_long, 0, MAVLINK_MSG_ID_COMMAND_LONG_LEN); |
---|
460 | memcpy(command_long, _MAV_PAYLOAD(msg), len); |
---|
461 | #endif |
---|
462 | } |
---|