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