mavlink_msg_command_ack.h 4.98 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2
// MESSAGE COMMAND_ACK PACKING

3
#define MAVLINK_MSG_ID_COMMAND_ACK 77
James Goppert's avatar
James Goppert committed
4

lm's avatar
lm committed
5
typedef struct __mavlink_command_ack_t
James Goppert's avatar
James Goppert committed
6
{
7
 uint16_t command; ///< Command ID, as defined by MAV_CMD enum.
8
 uint8_t result; ///< See MAV_RESULT enum
James Goppert's avatar
James Goppert committed
9 10
} mavlink_command_ack_t;

11 12
#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3
#define MAVLINK_MSG_ID_77_LEN 3
lm's avatar
lm committed
13 14 15 16 17 18



#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \
	"COMMAND_ACK", \
	2, \
19 20
	{  { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \
         { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \
lm's avatar
lm committed
21 22 23 24
         } \
}


James Goppert's avatar
James Goppert committed
25 26 27 28 29 30
/**
 * @brief Pack a command_ack 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
 *
31
 * @param command Command ID, as defined by MAV_CMD enum.
32
 * @param result See MAV_RESULT enum
James Goppert's avatar
James Goppert committed
33 34
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
35
static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
36
						       uint16_t command, uint8_t result)
James Goppert's avatar
James Goppert committed
37
{
LM's avatar
LM committed
38
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
39 40 41
	char buf[3];
	_mav_put_uint16_t(buf, 0, command);
	_mav_put_uint8_t(buf, 2, result);
LM's avatar
LM committed
42

43
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
LM's avatar
LM committed
44 45 46 47
#else
	mavlink_command_ack_t packet;
	packet.command = command;
	packet.result = result;
James Goppert's avatar
James Goppert committed
48

49
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
LM's avatar
LM committed
50
#endif
James Goppert's avatar
James Goppert committed
51

LM's avatar
LM committed
52
	msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
53
	return mavlink_finalize_message(msg, system_id, component_id, 3, 143);
James Goppert's avatar
James Goppert committed
54 55 56
}

/**
lm's avatar
lm committed
57
 * @brief Pack a command_ack message on a channel
James Goppert's avatar
James Goppert committed
58 59 60 61
 * @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 was sent over
 * @param msg The MAVLink message to compress the data into
62
 * @param command Command ID, as defined by MAV_CMD enum.
63
 * @param result See MAV_RESULT enum
James Goppert's avatar
James Goppert committed
64 65
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
66 67
static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
68
						           uint16_t command,uint8_t result)
lm's avatar
lm committed
69
{
LM's avatar
LM committed
70
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
71 72 73
	char buf[3];
	_mav_put_uint16_t(buf, 0, command);
	_mav_put_uint8_t(buf, 2, result);
lm's avatar
lm committed
74

75
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
LM's avatar
LM committed
76 77 78 79
#else
	mavlink_command_ack_t packet;
	packet.command = command;
	packet.result = result;
lm's avatar
lm committed
80

81
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
LM's avatar
LM committed
82 83 84
#endif

	msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
85
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 143);
lm's avatar
lm committed
86 87
}

James Goppert's avatar
James Goppert committed
88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104
/**
 * @brief Encode a command_ack struct into a 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 command_ack C-struct to read the message contents from
 */
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)
{
	return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result);
}

/**
 * @brief Send a command_ack message
 * @param chan MAVLink channel to send the message
 *
105
 * @param command Command ID, as defined by MAV_CMD enum.
106
 * @param result See MAV_RESULT enum
James Goppert's avatar
James Goppert committed
107
 */
lm's avatar
lm committed
108 109
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

110
static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result)
lm's avatar
lm committed
111
{
LM's avatar
LM committed
112
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
113 114 115
	char buf[3];
	_mav_put_uint16_t(buf, 0, command);
	_mav_put_uint8_t(buf, 2, result);
LM's avatar
LM committed
116

117
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, 3, 143);
LM's avatar
LM committed
118 119 120 121
#else
	mavlink_command_ack_t packet;
	packet.command = command;
	packet.result = result;
LM's avatar
LM committed
122

123
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, 3, 143);
LM's avatar
LM committed
124
#endif
James Goppert's avatar
James Goppert committed
125 126 127
}

#endif
lm's avatar
lm committed
128

James Goppert's avatar
James Goppert committed
129 130
// MESSAGE COMMAND_ACK UNPACKING

lm's avatar
lm committed
131

James Goppert's avatar
James Goppert committed
132 133 134
/**
 * @brief Get field command from command_ack message
 *
135
 * @return Command ID, as defined by MAV_CMD enum.
James Goppert's avatar
James Goppert committed
136
 */
137
static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
138
{
139
	return _MAV_RETURN_uint16_t(msg,  0);
James Goppert's avatar
James Goppert committed
140 141 142 143 144
}

/**
 * @brief Get field result from command_ack message
 *
145
 * @return See MAV_RESULT enum
James Goppert's avatar
James Goppert committed
146
 */
147
static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
148
{
149
	return _MAV_RETURN_uint8_t(msg,  2);
James Goppert's avatar
James Goppert committed
150 151 152 153 154 155 156 157 158 159
}

/**
 * @brief Decode a command_ack message into a struct
 *
 * @param msg The message to decode
 * @param command_ack C-struct to decode the message contents into
 */
static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack)
{
lm's avatar
lm committed
160 161 162 163
#if MAVLINK_NEED_BYTE_SWAP
	command_ack->command = mavlink_msg_command_ack_get_command(msg);
	command_ack->result = mavlink_msg_command_ack_get_result(msg);
#else
164
	memcpy(command_ack, _MAV_PAYLOAD(msg), 3);
lm's avatar
lm committed
165
#endif
James Goppert's avatar
James Goppert committed
166
}