1 | // MESSAGE COMMAND_ACK PACKING
|
---|
2 |
|
---|
3 | #define MAVLINK_MSG_ID_COMMAND_ACK 77
|
---|
4 |
|
---|
5 | typedef struct MAVLINK_PACKED __mavlink_command_ack_t
|
---|
6 | {
|
---|
7 | uint16_t command; /*< Command ID, as defined by MAV_CMD enum.*/
|
---|
8 | uint8_t result; /*< See MAV_RESULT enum*/
|
---|
9 | } mavlink_command_ack_t;
|
---|
10 |
|
---|
11 | #define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3
|
---|
12 | #define MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN 3
|
---|
13 | #define MAVLINK_MSG_ID_77_LEN 3
|
---|
14 | #define MAVLINK_MSG_ID_77_MIN_LEN 3
|
---|
15 |
|
---|
16 | #define MAVLINK_MSG_ID_COMMAND_ACK_CRC 143
|
---|
17 | #define MAVLINK_MSG_ID_77_CRC 143
|
---|
18 |
|
---|
19 |
|
---|
20 |
|
---|
21 | #if MAVLINK_COMMAND_24BIT
|
---|
22 | #define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \
|
---|
23 | 77, \
|
---|
24 | "COMMAND_ACK", \
|
---|
25 | 2, \
|
---|
26 | { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \
|
---|
27 | { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \
|
---|
28 | } \
|
---|
29 | }
|
---|
30 | #else
|
---|
31 | #define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \
|
---|
32 | "COMMAND_ACK", \
|
---|
33 | 2, \
|
---|
34 | { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \
|
---|
35 | { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \
|
---|
36 | } \
|
---|
37 | }
|
---|
38 | #endif
|
---|
39 |
|
---|
40 | /**
|
---|
41 | * @brief Pack a command_ack message
|
---|
42 | * @param system_id ID of this system
|
---|
43 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
44 | * @param msg The MAVLink message to compress the data into
|
---|
45 | *
|
---|
46 | * @param command Command ID, as defined by MAV_CMD enum.
|
---|
47 | * @param result See MAV_RESULT enum
|
---|
48 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
49 | */
|
---|
50 | static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
---|
51 | uint16_t command, uint8_t result)
|
---|
52 | {
|
---|
53 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
54 | char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN];
|
---|
55 | _mav_put_uint16_t(buf, 0, command);
|
---|
56 | _mav_put_uint8_t(buf, 2, result);
|
---|
57 |
|
---|
58 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
---|
59 | #else
|
---|
60 | mavlink_command_ack_t packet;
|
---|
61 | packet.command = command;
|
---|
62 | packet.result = result;
|
---|
63 |
|
---|
64 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
---|
65 | #endif
|
---|
66 |
|
---|
67 | msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
|
---|
68 | return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
---|
69 | }
|
---|
70 |
|
---|
71 | /**
|
---|
72 | * @brief Pack a command_ack message on a channel
|
---|
73 | * @param system_id ID of this system
|
---|
74 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
75 | * @param chan The MAVLink channel this message will be sent over
|
---|
76 | * @param msg The MAVLink message to compress the data into
|
---|
77 | * @param command Command ID, as defined by MAV_CMD enum.
|
---|
78 | * @param result See MAV_RESULT enum
|
---|
79 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
80 | */
|
---|
81 | static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
---|
82 | mavlink_message_t* msg,
|
---|
83 | uint16_t command,uint8_t result)
|
---|
84 | {
|
---|
85 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
86 | char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN];
|
---|
87 | _mav_put_uint16_t(buf, 0, command);
|
---|
88 | _mav_put_uint8_t(buf, 2, result);
|
---|
89 |
|
---|
90 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
---|
91 | #else
|
---|
92 | mavlink_command_ack_t packet;
|
---|
93 | packet.command = command;
|
---|
94 | packet.result = result;
|
---|
95 |
|
---|
96 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
---|
97 | #endif
|
---|
98 |
|
---|
99 | msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
|
---|
100 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
---|
101 | }
|
---|
102 |
|
---|
103 | /**
|
---|
104 | * @brief Encode a command_ack struct
|
---|
105 | *
|
---|
106 | * @param system_id ID of this system
|
---|
107 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
108 | * @param msg The MAVLink message to compress the data into
|
---|
109 | * @param command_ack C-struct to read the message contents from
|
---|
110 | */
|
---|
111 | 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)
|
---|
112 | {
|
---|
113 | return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result);
|
---|
114 | }
|
---|
115 |
|
---|
116 | /**
|
---|
117 | * @brief Encode a command_ack struct on a channel
|
---|
118 | *
|
---|
119 | * @param system_id ID of this system
|
---|
120 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
121 | * @param chan The MAVLink channel this message will be sent over
|
---|
122 | * @param msg The MAVLink message to compress the data into
|
---|
123 | * @param command_ack C-struct to read the message contents from
|
---|
124 | */
|
---|
125 | 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)
|
---|
126 | {
|
---|
127 | return mavlink_msg_command_ack_pack_chan(system_id, component_id, chan, msg, command_ack->command, command_ack->result);
|
---|
128 | }
|
---|
129 |
|
---|
130 | /**
|
---|
131 | * @brief Send a command_ack message
|
---|
132 | * @param chan MAVLink channel to send the message
|
---|
133 | *
|
---|
134 | * @param command Command ID, as defined by MAV_CMD enum.
|
---|
135 | * @param result See MAV_RESULT enum
|
---|
136 | */
|
---|
137 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
---|
138 |
|
---|
139 | static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result)
|
---|
140 | {
|
---|
141 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
142 | char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN];
|
---|
143 | _mav_put_uint16_t(buf, 0, command);
|
---|
144 | _mav_put_uint8_t(buf, 2, result);
|
---|
145 |
|
---|
146 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
---|
147 | #else
|
---|
148 | mavlink_command_ack_t packet;
|
---|
149 | packet.command = command;
|
---|
150 | packet.result = result;
|
---|
151 |
|
---|
152 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
---|
153 | #endif
|
---|
154 | }
|
---|
155 |
|
---|
156 | /**
|
---|
157 | * @brief Send a command_ack message
|
---|
158 | * @param chan MAVLink channel to send the message
|
---|
159 | * @param struct The MAVLink struct to serialize
|
---|
160 | */
|
---|
161 | static inline void mavlink_msg_command_ack_send_struct(mavlink_channel_t chan, const mavlink_command_ack_t* command_ack)
|
---|
162 | {
|
---|
163 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
164 | mavlink_msg_command_ack_send(chan, command_ack->command, command_ack->result);
|
---|
165 | #else
|
---|
166 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)command_ack, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
---|
167 | #endif
|
---|
168 | }
|
---|
169 |
|
---|
170 | #if MAVLINK_MSG_ID_COMMAND_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
---|
171 | /*
|
---|
172 | This varient of _send() can be used to save stack space by re-using
|
---|
173 | memory from the receive buffer. The caller provides a
|
---|
174 | mavlink_message_t which is the size of a full mavlink message. This
|
---|
175 | is usually the receive buffer for the channel, and allows a reply to an
|
---|
176 | incoming message with minimum stack space usage.
|
---|
177 | */
|
---|
178 | static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t command, uint8_t result)
|
---|
179 | {
|
---|
180 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
181 | char *buf = (char *)msgbuf;
|
---|
182 | _mav_put_uint16_t(buf, 0, command);
|
---|
183 | _mav_put_uint8_t(buf, 2, result);
|
---|
184 |
|
---|
185 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
---|
186 | #else
|
---|
187 | mavlink_command_ack_t *packet = (mavlink_command_ack_t *)msgbuf;
|
---|
188 | packet->command = command;
|
---|
189 | packet->result = result;
|
---|
190 |
|
---|
191 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
---|
192 | #endif
|
---|
193 | }
|
---|
194 | #endif
|
---|
195 |
|
---|
196 | #endif
|
---|
197 |
|
---|
198 | // MESSAGE COMMAND_ACK UNPACKING
|
---|
199 |
|
---|
200 |
|
---|
201 | /**
|
---|
202 | * @brief Get field command from command_ack message
|
---|
203 | *
|
---|
204 | * @return Command ID, as defined by MAV_CMD enum.
|
---|
205 | */
|
---|
206 | static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message_t* msg)
|
---|
207 | {
|
---|
208 | return _MAV_RETURN_uint16_t(msg, 0);
|
---|
209 | }
|
---|
210 |
|
---|
211 | /**
|
---|
212 | * @brief Get field result from command_ack message
|
---|
213 | *
|
---|
214 | * @return See MAV_RESULT enum
|
---|
215 | */
|
---|
216 | static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg)
|
---|
217 | {
|
---|
218 | return _MAV_RETURN_uint8_t(msg, 2);
|
---|
219 | }
|
---|
220 |
|
---|
221 | /**
|
---|
222 | * @brief Decode a command_ack message into a struct
|
---|
223 | *
|
---|
224 | * @param msg The message to decode
|
---|
225 | * @param command_ack C-struct to decode the message contents into
|
---|
226 | */
|
---|
227 | static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack)
|
---|
228 | {
|
---|
229 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
230 | command_ack->command = mavlink_msg_command_ack_get_command(msg);
|
---|
231 | command_ack->result = mavlink_msg_command_ack_get_result(msg);
|
---|
232 | #else
|
---|
233 | uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_ACK_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_ACK_LEN;
|
---|
234 | memset(command_ack, 0, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
---|
235 | memcpy(command_ack, _MAV_PAYLOAD(msg), len);
|
---|
236 | #endif
|
---|
237 | }
|
---|