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) }, \ 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 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 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);
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 343 return _MAV_RETURN_uint16_t(msg, 28);
363 return _MAV_RETURN_float(msg, 0);
373 return _MAV_RETURN_float(msg, 4);
383 return _MAV_RETURN_float(msg, 8);
393 return _MAV_RETURN_float(msg, 12);
403 return _MAV_RETURN_float(msg, 16);
413 return _MAV_RETURN_float(msg, 20);
423 return _MAV_RETURN_float(msg, 24);
434 #if MAVLINK_NEED_BYTE_SWAP #define _mav_put_float(buf, wire_offset, b)
static float mavlink_msg_command_long_get_param3(const mavlink_message_t *msg)
Get field param3 from command_long message.
static 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)
Pack a command_long message.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static void mavlink_msg_command_long_decode(const mavlink_message_t *msg, mavlink_command_long_t *command_long)
Decode a command_long message into a struct.
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.
#define _mav_put_uint8_t(buf, wire_offset, b)
static uint8_t mavlink_msg_command_long_get_target_system(const mavlink_message_t *msg)
Send a command_long message.
#define _MAV_PAYLOAD_NON_CONST(msg)
static float mavlink_msg_command_long_get_param5(const mavlink_message_t *msg)
Get field param5 from command_long message.
static float mavlink_msg_command_long_get_param4(const mavlink_message_t *msg)
Get field param4 from command_long message.
static float mavlink_msg_command_long_get_param7(const mavlink_message_t *msg)
Get field param7 from command_long message.
static uint8_t mavlink_msg_command_long_get_target_component(const mavlink_message_t *msg)
Get field target_component from command_long message.
#define MAVLINK_MSG_ID_COMMAND_LONG_LEN
#define _MAV_PAYLOAD(msg)
#define MAVLINK_MSG_ID_COMMAND_LONG
#define MAVLINK_MSG_ID_COMMAND_LONG_CRC
static uint16_t mavlink_msg_command_long_get_command(const mavlink_message_t *msg)
Get field command from command_long message.
static 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)
Encode a command_long struct on a channel.
static 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)
Pack a command_long message on a channel.
static float mavlink_msg_command_long_get_param6(const mavlink_message_t *msg)
Get field param6 from command_long message.
static float mavlink_msg_command_long_get_param1(const mavlink_message_t *msg)
Get field param1 from command_long message.
#define _mav_put_uint16_t(buf, wire_offset, b)
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.
static 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)
Encode a command_long struct.
static uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_message_t *msg)
Get field confirmation from command_long message.
static float mavlink_msg_command_long_get_param2(const mavlink_message_t *msg)
Get field param2 from command_long message.