2 // MESSAGE COMMAND_LONG PACKING
4 #define MAVLINK_MSG_ID_COMMAND_LONG 76
7 typedef struct __mavlink_command_long_t
{
8 float param1
; /*< Parameter 1, as defined by MAV_CMD enum.*/
9 float param2
; /*< Parameter 2, as defined by MAV_CMD enum.*/
10 float param3
; /*< Parameter 3, as defined by MAV_CMD enum.*/
11 float param4
; /*< Parameter 4, as defined by MAV_CMD enum.*/
12 float param5
; /*< Parameter 5, as defined by MAV_CMD enum.*/
13 float param6
; /*< Parameter 6, as defined by MAV_CMD enum.*/
14 float param7
; /*< Parameter 7, as defined by MAV_CMD enum.*/
15 uint16_t command
; /*< Command ID, as defined by MAV_CMD enum.*/
16 uint8_t target_system
; /*< System which should execute the command*/
17 uint8_t target_component
; /*< Component which should execute the command, 0 for all components*/
18 uint8_t confirmation
; /*< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)*/
19 }) mavlink_command_long_t
;
21 #define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33
22 #define MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN 33
23 #define MAVLINK_MSG_ID_76_LEN 33
24 #define MAVLINK_MSG_ID_76_MIN_LEN 33
26 #define MAVLINK_MSG_ID_COMMAND_LONG_CRC 152
27 #define MAVLINK_MSG_ID_76_CRC 152
31 #if MAVLINK_COMMAND_24BIT
32 #define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \
36 { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \
37 { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \
38 { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \
39 { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \
40 { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \
41 { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \
42 { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \
43 { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \
44 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \
45 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \
46 { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \
50 #define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \
53 { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \
54 { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \
55 { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \
56 { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \
57 { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \
58 { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \
59 { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \
60 { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \
61 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \
62 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \
63 { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \
69 * @brief Pack a command_long message
70 * @param system_id ID of this system
71 * @param component_id ID of this component (e.g. 200 for IMU)
72 * @param msg The MAVLink message to compress the data into
74 * @param target_system System which should execute the command
75 * @param target_component Component which should execute the command, 0 for all components
76 * @param command Command ID, as defined by MAV_CMD enum.
77 * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
78 * @param param1 Parameter 1, as defined by MAV_CMD enum.
79 * @param param2 Parameter 2, as defined by MAV_CMD enum.
80 * @param param3 Parameter 3, as defined by MAV_CMD enum.
81 * @param param4 Parameter 4, as defined by MAV_CMD enum.
82 * @param param5 Parameter 5, as defined by MAV_CMD enum.
83 * @param param6 Parameter 6, as defined by MAV_CMD enum.
84 * @param param7 Parameter 7, as defined by MAV_CMD enum.
85 * @return length of the message in bytes (excluding serial stream start sign)
87 static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
88 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
)
90 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
91 char buf
[MAVLINK_MSG_ID_COMMAND_LONG_LEN
];
92 _mav_put_float(buf
, 0, param1
);
93 _mav_put_float(buf
, 4, param2
);
94 _mav_put_float(buf
, 8, param3
);
95 _mav_put_float(buf
, 12, param4
);
96 _mav_put_float(buf
, 16, param5
);
97 _mav_put_float(buf
, 20, param6
);
98 _mav_put_float(buf
, 24, param7
);
99 _mav_put_uint16_t(buf
, 28, command
);
100 _mav_put_uint8_t(buf
, 30, target_system
);
101 _mav_put_uint8_t(buf
, 31, target_component
);
102 _mav_put_uint8_t(buf
, 32, confirmation
);
104 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_COMMAND_LONG_LEN
);
106 mavlink_command_long_t packet
;
107 packet
.param1
= param1
;
108 packet
.param2
= param2
;
109 packet
.param3
= param3
;
110 packet
.param4
= param4
;
111 packet
.param5
= param5
;
112 packet
.param6
= param6
;
113 packet
.param7
= param7
;
114 packet
.command
= command
;
115 packet
.target_system
= target_system
;
116 packet
.target_component
= target_component
;
117 packet
.confirmation
= confirmation
;
119 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_COMMAND_LONG_LEN
);
122 msg
->msgid
= MAVLINK_MSG_ID_COMMAND_LONG
;
123 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
);
127 * @brief Pack a command_long message on a channel
128 * @param system_id ID of this system
129 * @param component_id ID of this component (e.g. 200 for IMU)
130 * @param chan The MAVLink channel this message will be sent over
131 * @param msg The MAVLink message to compress the data into
132 * @param target_system System which should execute the command
133 * @param target_component Component which should execute the command, 0 for all components
134 * @param command Command ID, as defined by MAV_CMD enum.
135 * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
136 * @param param1 Parameter 1, as defined by MAV_CMD enum.
137 * @param param2 Parameter 2, as defined by MAV_CMD enum.
138 * @param param3 Parameter 3, as defined by MAV_CMD enum.
139 * @param param4 Parameter 4, as defined by MAV_CMD enum.
140 * @param param5 Parameter 5, as defined by MAV_CMD enum.
141 * @param param6 Parameter 6, as defined by MAV_CMD enum.
142 * @param param7 Parameter 7, as defined by MAV_CMD enum.
143 * @return length of the message in bytes (excluding serial stream start sign)
145 static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
146 mavlink_message_t
* msg
,
147 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
)
149 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
150 char buf
[MAVLINK_MSG_ID_COMMAND_LONG_LEN
];
151 _mav_put_float(buf
, 0, param1
);
152 _mav_put_float(buf
, 4, param2
);
153 _mav_put_float(buf
, 8, param3
);
154 _mav_put_float(buf
, 12, param4
);
155 _mav_put_float(buf
, 16, param5
);
156 _mav_put_float(buf
, 20, param6
);
157 _mav_put_float(buf
, 24, param7
);
158 _mav_put_uint16_t(buf
, 28, command
);
159 _mav_put_uint8_t(buf
, 30, target_system
);
160 _mav_put_uint8_t(buf
, 31, target_component
);
161 _mav_put_uint8_t(buf
, 32, confirmation
);
163 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_COMMAND_LONG_LEN
);
165 mavlink_command_long_t packet
;
166 packet
.param1
= param1
;
167 packet
.param2
= param2
;
168 packet
.param3
= param3
;
169 packet
.param4
= param4
;
170 packet
.param5
= param5
;
171 packet
.param6
= param6
;
172 packet
.param7
= param7
;
173 packet
.command
= command
;
174 packet
.target_system
= target_system
;
175 packet
.target_component
= target_component
;
176 packet
.confirmation
= confirmation
;
178 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_COMMAND_LONG_LEN
);
181 msg
->msgid
= MAVLINK_MSG_ID_COMMAND_LONG
;
182 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
);
186 * @brief Encode a command_long struct
188 * @param system_id ID of this system
189 * @param component_id ID of this component (e.g. 200 for IMU)
190 * @param msg The MAVLink message to compress the data into
191 * @param command_long C-struct to read the message contents from
193 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
)
195 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
);
199 * @brief Encode a command_long struct on a channel
201 * @param system_id ID of this system
202 * @param component_id ID of this component (e.g. 200 for IMU)
203 * @param chan The MAVLink channel this message will be sent over
204 * @param msg The MAVLink message to compress the data into
205 * @param command_long C-struct to read the message contents from
207 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
)
209 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
);
213 * @brief Send a command_long message
214 * @param chan MAVLink channel to send the message
216 * @param target_system System which should execute the command
217 * @param target_component Component which should execute the command, 0 for all components
218 * @param command Command ID, as defined by MAV_CMD enum.
219 * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
220 * @param param1 Parameter 1, as defined by MAV_CMD enum.
221 * @param param2 Parameter 2, as defined by MAV_CMD enum.
222 * @param param3 Parameter 3, as defined by MAV_CMD enum.
223 * @param param4 Parameter 4, as defined by MAV_CMD enum.
224 * @param param5 Parameter 5, as defined by MAV_CMD enum.
225 * @param param6 Parameter 6, as defined by MAV_CMD enum.
226 * @param param7 Parameter 7, as defined by MAV_CMD enum.
228 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
230 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
)
232 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
233 char buf
[MAVLINK_MSG_ID_COMMAND_LONG_LEN
];
234 _mav_put_float(buf
, 0, param1
);
235 _mav_put_float(buf
, 4, param2
);
236 _mav_put_float(buf
, 8, param3
);
237 _mav_put_float(buf
, 12, param4
);
238 _mav_put_float(buf
, 16, param5
);
239 _mav_put_float(buf
, 20, param6
);
240 _mav_put_float(buf
, 24, param7
);
241 _mav_put_uint16_t(buf
, 28, command
);
242 _mav_put_uint8_t(buf
, 30, target_system
);
243 _mav_put_uint8_t(buf
, 31, target_component
);
244 _mav_put_uint8_t(buf
, 32, confirmation
);
246 _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
);
248 mavlink_command_long_t packet
;
249 packet
.param1
= param1
;
250 packet
.param2
= param2
;
251 packet
.param3
= param3
;
252 packet
.param4
= param4
;
253 packet
.param5
= param5
;
254 packet
.param6
= param6
;
255 packet
.param7
= param7
;
256 packet
.command
= command
;
257 packet
.target_system
= target_system
;
258 packet
.target_component
= target_component
;
259 packet
.confirmation
= confirmation
;
261 _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
);
266 * @brief Send a command_long message
267 * @param chan MAVLink channel to send the message
268 * @param struct The MAVLink struct to serialize
270 static inline void mavlink_msg_command_long_send_struct(mavlink_channel_t chan
, const mavlink_command_long_t
* command_long
)
272 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
273 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
);
275 _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
);
279 #if MAVLINK_MSG_ID_COMMAND_LONG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
281 This varient of _send() can be used to save stack space by re-using
282 memory from the receive buffer. The caller provides a
283 mavlink_message_t which is the size of a full mavlink message. This
284 is usually the receive buffer for the channel, and allows a reply to an
285 incoming message with minimum stack space usage.
287 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
)
289 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
290 char *buf
= (char *)msgbuf
;
291 _mav_put_float(buf
, 0, param1
);
292 _mav_put_float(buf
, 4, param2
);
293 _mav_put_float(buf
, 8, param3
);
294 _mav_put_float(buf
, 12, param4
);
295 _mav_put_float(buf
, 16, param5
);
296 _mav_put_float(buf
, 20, param6
);
297 _mav_put_float(buf
, 24, param7
);
298 _mav_put_uint16_t(buf
, 28, command
);
299 _mav_put_uint8_t(buf
, 30, target_system
);
300 _mav_put_uint8_t(buf
, 31, target_component
);
301 _mav_put_uint8_t(buf
, 32, confirmation
);
303 _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
);
305 mavlink_command_long_t
*packet
= (mavlink_command_long_t
*)msgbuf
;
306 packet
->param1
= param1
;
307 packet
->param2
= param2
;
308 packet
->param3
= param3
;
309 packet
->param4
= param4
;
310 packet
->param5
= param5
;
311 packet
->param6
= param6
;
312 packet
->param7
= param7
;
313 packet
->command
= command
;
314 packet
->target_system
= target_system
;
315 packet
->target_component
= target_component
;
316 packet
->confirmation
= confirmation
;
318 _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
);
325 // MESSAGE COMMAND_LONG UNPACKING
329 * @brief Get field target_system from command_long message
331 * @return System which should execute the command
333 static inline uint8_t mavlink_msg_command_long_get_target_system(const mavlink_message_t
* msg
)
335 return _MAV_RETURN_uint8_t(msg
, 30);
339 * @brief Get field target_component from command_long message
341 * @return Component which should execute the command, 0 for all components
343 static inline uint8_t mavlink_msg_command_long_get_target_component(const mavlink_message_t
* msg
)
345 return _MAV_RETURN_uint8_t(msg
, 31);
349 * @brief Get field command from command_long message
351 * @return Command ID, as defined by MAV_CMD enum.
353 static inline uint16_t mavlink_msg_command_long_get_command(const mavlink_message_t
* msg
)
355 return _MAV_RETURN_uint16_t(msg
, 28);
359 * @brief Get field confirmation from command_long message
361 * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
363 static inline uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_message_t
* msg
)
365 return _MAV_RETURN_uint8_t(msg
, 32);
369 * @brief Get field param1 from command_long message
371 * @return Parameter 1, as defined by MAV_CMD enum.
373 static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t
* msg
)
375 return _MAV_RETURN_float(msg
, 0);
379 * @brief Get field param2 from command_long message
381 * @return Parameter 2, as defined by MAV_CMD enum.
383 static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t
* msg
)
385 return _MAV_RETURN_float(msg
, 4);
389 * @brief Get field param3 from command_long message
391 * @return Parameter 3, as defined by MAV_CMD enum.
393 static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t
* msg
)
395 return _MAV_RETURN_float(msg
, 8);
399 * @brief Get field param4 from command_long message
401 * @return Parameter 4, as defined by MAV_CMD enum.
403 static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t
* msg
)
405 return _MAV_RETURN_float(msg
, 12);
409 * @brief Get field param5 from command_long message
411 * @return Parameter 5, as defined by MAV_CMD enum.
413 static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t
* msg
)
415 return _MAV_RETURN_float(msg
, 16);
419 * @brief Get field param6 from command_long message
421 * @return Parameter 6, as defined by MAV_CMD enum.
423 static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t
* msg
)
425 return _MAV_RETURN_float(msg
, 20);
429 * @brief Get field param7 from command_long message
431 * @return Parameter 7, as defined by MAV_CMD enum.
433 static inline float mavlink_msg_command_long_get_param7(const mavlink_message_t
* msg
)
435 return _MAV_RETURN_float(msg
, 24);
439 * @brief Decode a command_long message into a struct
441 * @param msg The message to decode
442 * @param command_long C-struct to decode the message contents into
444 static inline void mavlink_msg_command_long_decode(const mavlink_message_t
* msg
, mavlink_command_long_t
* command_long
)
446 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
447 command_long
->param1
= mavlink_msg_command_long_get_param1(msg
);
448 command_long
->param2
= mavlink_msg_command_long_get_param2(msg
);
449 command_long
->param3
= mavlink_msg_command_long_get_param3(msg
);
450 command_long
->param4
= mavlink_msg_command_long_get_param4(msg
);
451 command_long
->param5
= mavlink_msg_command_long_get_param5(msg
);
452 command_long
->param6
= mavlink_msg_command_long_get_param6(msg
);
453 command_long
->param7
= mavlink_msg_command_long_get_param7(msg
);
454 command_long
->command
= mavlink_msg_command_long_get_command(msg
);
455 command_long
->target_system
= mavlink_msg_command_long_get_target_system(msg
);
456 command_long
->target_component
= mavlink_msg_command_long_get_target_component(msg
);
457 command_long
->confirmation
= mavlink_msg_command_long_get_confirmation(msg
);
459 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_COMMAND_LONG_LEN
? msg
->len
: MAVLINK_MSG_ID_COMMAND_LONG_LEN
;
460 memset(command_long
, 0, MAVLINK_MSG_ID_COMMAND_LONG_LEN
);
461 memcpy(command_long
, _MAV_PAYLOAD(msg
), len
);