3 #define MAVLINK_MSG_ID_COMMAND_LONG 76
20 #define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33
21 #define MAVLINK_MSG_ID_76_LEN 33
23 #define MAVLINK_MSG_ID_COMMAND_LONG_CRC 152
24 #define MAVLINK_MSG_ID_76_CRC 152
28 #define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \
31 { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \
32 { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \
33 { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \
34 { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \
35 { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \
36 { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \
37 { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \
38 { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \
39 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \
40 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \
41 { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \
65 static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
66 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)
68 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
101 #if MAVLINK_CRC_EXTRA
127 static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
128 mavlink_message_t* msg,
129 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)
131 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
164 #if MAVLINK_CRC_EXTRA
179 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)
181 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);
193 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)
195 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);
214 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
216 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)
218 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
232 #if MAVLINK_CRC_EXTRA
251 #if MAVLINK_CRC_EXTRA
259 #if MAVLINK_MSG_ID_COMMAND_LONG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
267 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)
269 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
270 char *buf = (
char *)msgbuf;
283 #if MAVLINK_CRC_EXTRA
302 #if MAVLINK_CRC_EXTRA
321 static inline uint8_t mavlink_msg_command_long_get_target_system(
const mavlink_message_t* msg)
331 static inline uint8_t mavlink_msg_command_long_get_target_component(
const mavlink_message_t* msg)
341 static inline uint16_t mavlink_msg_command_long_get_command(
const mavlink_message_t* msg)
343 return _MAV_RETURN_uint16_t(msg, 28);
351 static inline uint8_t mavlink_msg_command_long_get_confirmation(
const mavlink_message_t* msg)
361 static inline float mavlink_msg_command_long_get_param1(
const mavlink_message_t* msg)
363 return _MAV_RETURN_float(msg, 0);
371 static inline float mavlink_msg_command_long_get_param2(
const mavlink_message_t* msg)
373 return _MAV_RETURN_float(msg, 4);
381 static inline float mavlink_msg_command_long_get_param3(
const mavlink_message_t* msg)
383 return _MAV_RETURN_float(msg, 8);
391 static inline float mavlink_msg_command_long_get_param4(
const mavlink_message_t* msg)
393 return _MAV_RETURN_float(msg, 12);
401 static inline float mavlink_msg_command_long_get_param5(
const mavlink_message_t* msg)
403 return _MAV_RETURN_float(msg, 16);
411 static inline float mavlink_msg_command_long_get_param6(
const mavlink_message_t* msg)
413 return _MAV_RETURN_float(msg, 20);
421 static inline float mavlink_msg_command_long_get_param7(
const mavlink_message_t* msg)
423 return _MAV_RETURN_float(msg, 24);
432 static inline void mavlink_msg_command_long_decode(
const mavlink_message_t* msg,
mavlink_command_long_t* command_long)
434 #if MAVLINK_NEED_BYTE_SWAP
435 command_long->
param1 = mavlink_msg_command_long_get_param1(msg);
436 command_long->
param2 = mavlink_msg_command_long_get_param2(msg);
437 command_long->
param3 = mavlink_msg_command_long_get_param3(msg);
438 command_long->
param4 = mavlink_msg_command_long_get_param4(msg);
439 command_long->
param5 = mavlink_msg_command_long_get_param5(msg);
440 command_long->
param6 = mavlink_msg_command_long_get_param6(msg);
441 command_long->
param7 = mavlink_msg_command_long_get_param7(msg);
442 command_long->
command = mavlink_msg_command_long_get_command(msg);
443 command_long->
target_system = mavlink_msg_command_long_get_target_system(msg);
444 command_long->
target_component = mavlink_msg_command_long_get_target_component(msg);
445 command_long->
confirmation = mavlink_msg_command_long_get_confirmation(msg);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
Definition: mavlink_msg_command_long.h:5
struct __mavlink_command_long_t mavlink_command_long_t
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
uint16_t command
Command ID, as defined by MAV_CMD enum.
Definition: mavlink_msg_command_long.h:14
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
float param7
Parameter 7, as defined by MAV_CMD enum.
Definition: mavlink_msg_command_long.h:13
mavlink_channel_t
Definition: mavlink_types.h:178
float param6
Parameter 6, as defined by MAV_CMD enum.
Definition: mavlink_msg_command_long.h:12
#define MAVLINK_MSG_ID_COMMAND_LONG_LEN
Definition: mavlink_msg_command_long.h:20
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
#define MAVLINK_MSG_ID_COMMAND_LONG
Definition: mavlink_msg_command_long.h:3
#define MAVLINK_MSG_ID_COMMAND_LONG_CRC
Definition: mavlink_msg_command_long.h:23
float param1
Parameter 1, as defined by MAV_CMD enum.
Definition: mavlink_msg_command_long.h:7
float param5
Parameter 5, as defined by MAV_CMD enum.
Definition: mavlink_msg_command_long.h:11
uint8_t target_component
Component which should execute the command, 0 for all components.
Definition: mavlink_msg_command_long.h:16
float param2
Parameter 2, as defined by MAV_CMD enum.
Definition: mavlink_msg_command_long.h:8
uint8_t target_system
System which should execute the command.
Definition: mavlink_msg_command_long.h:15
float param4
Parameter 4, as defined by MAV_CMD enum.
Definition: mavlink_msg_command_long.h:10
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
float param3
Parameter 3, as defined by MAV_CMD enum.
Definition: mavlink_msg_command_long.h:9
uint8_t confirmation
0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) ...
Definition: mavlink_msg_command_long.h:17
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71