3 #define MAVLINK_MSG_ID_COMMAND_INT 75 22 #define MAVLINK_MSG_ID_COMMAND_INT_LEN 35 23 #define MAVLINK_MSG_ID_75_LEN 35 25 #define MAVLINK_MSG_ID_COMMAND_INT_CRC 158 26 #define MAVLINK_MSG_ID_75_CRC 158 30 #define MAVLINK_MESSAGE_INFO_COMMAND_INT { \ 33 { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \ 34 { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \ 35 { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \ 36 { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \ 37 { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \ 38 { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \ 39 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \ 40 { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \ 41 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \ 42 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \ 43 { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \ 44 { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \ 45 { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \ 72 uint8_t
target_system, uint8_t
target_component, uint8_t
frame, uint16_t
command, uint8_t
current, uint8_t
autocontinue,
float param1,
float param2,
float param3,
float param4, int32_t
x, int32_t
y,
float z)
74 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 111 #if MAVLINK_CRC_EXTRA 140 mavlink_message_t* msg,
141 uint8_t
target_system,uint8_t
target_component,uint8_t
frame,uint16_t
command,uint8_t
current,uint8_t
autocontinue,
float param1,
float param2,
float param3,
float param4,int32_t
x,int32_t
y,
float z)
143 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 180 #if MAVLINK_CRC_EXTRA 197 return mavlink_msg_command_int_pack(system_id, component_id, msg, command_int->
target_system, command_int->
target_component, command_int->
frame, command_int->
command, command_int->
current, command_int->
autocontinue, command_int->
param1, command_int->
param2, command_int->
param3, command_int->
param4, command_int->
x, command_int->
y, command_int->
z);
211 return mavlink_msg_command_int_pack_chan(system_id, component_id, chan, msg, command_int->
target_system, command_int->
target_component, command_int->
frame, command_int->
command, command_int->
current, command_int->
autocontinue, command_int->
param1, command_int->
param2, command_int->
param3, command_int->
param4, command_int->
x, command_int->
y, command_int->
z);
232 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 234 static inline void mavlink_msg_command_int_send(
mavlink_channel_t chan, uint8_t
target_system, uint8_t
target_component, uint8_t
frame, uint16_t
command, uint8_t
current, uint8_t
autocontinue,
float param1,
float param2,
float param3,
float param4, int32_t
x, int32_t
y,
float z)
236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 252 #if MAVLINK_CRC_EXTRA 273 #if MAVLINK_CRC_EXTRA 281 #if MAVLINK_MSG_ID_COMMAND_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN 289 static inline void mavlink_msg_command_int_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint8_t
target_system, uint8_t
target_component, uint8_t
frame, uint16_t
command, uint8_t
current, uint8_t
autocontinue,
float param1,
float param2,
float param3,
float param4, int32_t
x, int32_t
y,
float z)
291 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 292 char *buf = (
char *)msgbuf;
307 #if MAVLINK_CRC_EXTRA 328 #if MAVLINK_CRC_EXTRA 379 return _MAV_RETURN_uint16_t(msg, 28);
409 return _MAV_RETURN_float(msg, 0);
419 return _MAV_RETURN_float(msg, 4);
429 return _MAV_RETURN_float(msg, 8);
439 return _MAV_RETURN_float(msg, 12);
449 return _MAV_RETURN_int32_t(msg, 16);
459 return _MAV_RETURN_int32_t(msg, 20);
469 return _MAV_RETURN_float(msg, 24);
480 #if MAVLINK_NEED_BYTE_SWAP #define _mav_put_float(buf, wire_offset, b)
static uint8_t mavlink_msg_command_int_get_target_system(const mavlink_message_t *msg)
Send a command_int message.
static float mavlink_msg_command_int_get_param3(const mavlink_message_t *msg)
Get field param3 from command_int message.
static float mavlink_msg_command_int_get_z(const mavlink_message_t *msg)
Get field z from command_int message.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static uint8_t mavlink_msg_command_int_get_frame(const mavlink_message_t *msg)
Get field frame from command_int message.
static void mavlink_msg_command_int_decode(const mavlink_message_t *msg, mavlink_command_int_t *command_int)
Decode a command_int message into a struct.
static uint8_t mavlink_msg_command_int_get_target_component(const mavlink_message_t *msg)
Get field target_component from command_int message.
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)
#define _mav_put_int32_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint8_t mavlink_msg_command_int_get_autocontinue(const mavlink_message_t *msg)
Get field autocontinue from command_int message.
#define MAVLINK_MSG_ID_COMMAND_INT_CRC
struct __mavlink_command_int_t mavlink_command_int_t
static uint16_t mavlink_msg_command_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_command_int_t *command_int)
Encode a command_int struct on a channel.
#define _MAV_PAYLOAD(msg)
static uint16_t mavlink_msg_command_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_command_int_t *command_int)
Encode a command_int struct.
static float mavlink_msg_command_int_get_param4(const mavlink_message_t *msg)
Get field param4 from command_int message.
static float mavlink_msg_command_int_get_param2(const mavlink_message_t *msg)
Get field param2 from command_int message.
static uint8_t mavlink_msg_command_int_get_current(const mavlink_message_t *msg)
Get field current from command_int message.
static uint16_t mavlink_msg_command_int_get_command(const mavlink_message_t *msg)
Get field command from command_int message.
#define MAVLINK_MSG_ID_COMMAND_INT
static uint16_t mavlink_msg_command_int_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, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z)
Pack a command_int message on a channel.
#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_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z)
Pack a command_int message.
static int32_t mavlink_msg_command_int_get_y(const mavlink_message_t *msg)
Get field y from command_int message.
#define MAVLINK_MSG_ID_COMMAND_INT_LEN
static float mavlink_msg_command_int_get_param1(const mavlink_message_t *msg)
Get field param1 from command_int message.
static int32_t mavlink_msg_command_int_get_x(const mavlink_message_t *msg)
Get field x from command_int message.