3 #define MAVLINK_MSG_ID_COMMAND_ACK 77
11 #define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3
12 #define MAVLINK_MSG_ID_77_LEN 3
14 #define MAVLINK_MSG_ID_COMMAND_ACK_CRC 143
15 #define MAVLINK_MSG_ID_77_CRC 143
19 #define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \
22 { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \
23 { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \
38 static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
39 uint16_t command, uint8_t result)
41 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
73 static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
74 mavlink_message_t* msg,
75 uint16_t command,uint8_t result)
77 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
107 static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_command_ack_t* command_ack)
109 return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->
command, command_ack->
result);
121 static inline uint16_t mavlink_msg_command_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_command_ack_t* command_ack)
123 return mavlink_msg_command_ack_pack_chan(system_id, component_id, chan, msg, command_ack->
command, command_ack->
result);
133 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
135 static inline void mavlink_msg_command_ack_send(
mavlink_channel_t chan, uint16_t command, uint8_t result)
137 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
142 #if MAVLINK_CRC_EXTRA
152 #if MAVLINK_CRC_EXTRA
160 #if MAVLINK_MSG_ID_COMMAND_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
168 static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint16_t command, uint8_t result)
170 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
171 char *buf = (
char *)msgbuf;
175 #if MAVLINK_CRC_EXTRA
185 #if MAVLINK_CRC_EXTRA
204 static inline uint16_t mavlink_msg_command_ack_get_command(
const mavlink_message_t* msg)
206 return _MAV_RETURN_uint16_t(msg, 0);
214 static inline uint8_t mavlink_msg_command_ack_get_result(
const mavlink_message_t* msg)
225 static inline void mavlink_msg_command_ack_decode(
const mavlink_message_t* msg,
mavlink_command_ack_t* command_ack)
227 #if MAVLINK_NEED_BYTE_SWAP
228 command_ack->
command = mavlink_msg_command_ack_get_command(msg);
229 command_ack->
result = mavlink_msg_command_ack_get_result(msg);
#define MAVLINK_MSG_ID_COMMAND_ACK_LEN
Definition: mavlink_msg_command_ack.h:11
Definition: mavlink_msg_command_ack.h:5
#define MAVLINK_MSG_ID_COMMAND_ACK_CRC
Definition: mavlink_msg_command_ack.h:14
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
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
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
struct __mavlink_command_ack_t mavlink_command_ack_t
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
#define MAVLINK_MSG_ID_COMMAND_ACK
Definition: mavlink_msg_command_ack.h:3
uint8_t result
See MAV_RESULT enum.
Definition: mavlink_msg_command_ack.h:8
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
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
uint16_t command
Command ID, as defined by MAV_CMD enum.
Definition: mavlink_msg_command_ack.h:7