mavlink_msg_command_ack.h 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400
  1. #pragma once
  2. // MESSAGE COMMAND_ACK PACKING
  3. #define MAVLINK_MSG_ID_COMMAND_ACK 77
  4. typedef struct __mavlink_command_ack_t {
  5. uint16_t command; /*< Command ID (of acknowledged command).*/
  6. uint8_t result; /*< Result of command.*/
  7. uint8_t progress; /*< [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown.*/
  8. int32_t result_param2; /*< Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown").*/
  9. uint8_t target_system; /*< System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.*/
  10. uint8_t target_component; /*< Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.*/
  11. } mavlink_command_ack_t;
  12. #define MAVLINK_MSG_ID_COMMAND_ACK_LEN 10
  13. #define MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN 3
  14. #define MAVLINK_MSG_ID_77_LEN 10
  15. #define MAVLINK_MSG_ID_77_MIN_LEN 3
  16. #define MAVLINK_MSG_ID_COMMAND_ACK_CRC 143
  17. #define MAVLINK_MSG_ID_77_CRC 143
  18. #if MAVLINK_COMMAND_24BIT
  19. #define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \
  20. 77, \
  21. "COMMAND_ACK", \
  22. 6, \
  23. { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \
  24. { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \
  25. { "progress", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_ack_t, progress) }, \
  26. { "result_param2", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_command_ack_t, result_param2) }, \
  27. { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_command_ack_t, target_system) }, \
  28. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_command_ack_t, target_component) }, \
  29. } \
  30. }
  31. #else
  32. #define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \
  33. "COMMAND_ACK", \
  34. 6, \
  35. { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \
  36. { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \
  37. { "progress", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_ack_t, progress) }, \
  38. { "result_param2", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_command_ack_t, result_param2) }, \
  39. { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_command_ack_t, target_system) }, \
  40. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_command_ack_t, target_component) }, \
  41. } \
  42. }
  43. #endif
  44. /**
  45. * @brief Pack a command_ack message
  46. * @param system_id ID of this system
  47. * @param component_id ID of this component (e.g. 200 for IMU)
  48. * @param msg The MAVLink message to compress the data into
  49. *
  50. * @param command Command ID (of acknowledged command).
  51. * @param result Result of command.
  52. * @param progress [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown.
  53. * @param result_param2 Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown").
  54. * @param target_system System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
  55. * @param target_component Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
  56. * @return length of the message in bytes (excluding serial stream start sign)
  57. */
  58. static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  59. uint16_t command, uint8_t result, uint8_t progress, int32_t result_param2, uint8_t target_system, uint8_t target_component)
  60. {
  61. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  62. char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN];
  63. _mav_put_uint16_t(buf, 0, command);
  64. _mav_put_uint8_t(buf, 2, result);
  65. _mav_put_uint8_t(buf, 3, progress);
  66. _mav_put_int32_t(buf, 4, result_param2);
  67. _mav_put_uint8_t(buf, 8, target_system);
  68. _mav_put_uint8_t(buf, 9, target_component);
  69. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
  70. #else
  71. mavlink_command_ack_t packet;
  72. packet.command = command;
  73. packet.result = result;
  74. packet.progress = progress;
  75. packet.result_param2 = result_param2;
  76. packet.target_system = target_system;
  77. packet.target_component = target_component;
  78. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
  79. #endif
  80. msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
  81. 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);
  82. }
  83. /**
  84. * @brief Pack a command_ack message
  85. * @param system_id ID of this system
  86. * @param component_id ID of this component (e.g. 200 for IMU)
  87. * @param status MAVLink status structure
  88. * @param msg The MAVLink message to compress the data into
  89. *
  90. * @param command Command ID (of acknowledged command).
  91. * @param result Result of command.
  92. * @param progress [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown.
  93. * @param result_param2 Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown").
  94. * @param target_system System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
  95. * @param target_component Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
  96. * @return length of the message in bytes (excluding serial stream start sign)
  97. */
  98. static inline uint16_t mavlink_msg_command_ack_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  99. uint16_t command, uint8_t result, uint8_t progress, int32_t result_param2, uint8_t target_system, uint8_t target_component)
  100. {
  101. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  102. char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN];
  103. _mav_put_uint16_t(buf, 0, command);
  104. _mav_put_uint8_t(buf, 2, result);
  105. _mav_put_uint8_t(buf, 3, progress);
  106. _mav_put_int32_t(buf, 4, result_param2);
  107. _mav_put_uint8_t(buf, 8, target_system);
  108. _mav_put_uint8_t(buf, 9, target_component);
  109. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
  110. #else
  111. mavlink_command_ack_t packet;
  112. packet.command = command;
  113. packet.result = result;
  114. packet.progress = progress;
  115. packet.result_param2 = result_param2;
  116. packet.target_system = target_system;
  117. packet.target_component = target_component;
  118. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
  119. #endif
  120. msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
  121. #if MAVLINK_CRC_EXTRA
  122. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
  123. #else
  124. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
  125. #endif
  126. }
  127. /**
  128. * @brief Pack a command_ack message on a channel
  129. * @param system_id ID of this system
  130. * @param component_id ID of this component (e.g. 200 for IMU)
  131. * @param chan The MAVLink channel this message will be sent over
  132. * @param msg The MAVLink message to compress the data into
  133. * @param command Command ID (of acknowledged command).
  134. * @param result Result of command.
  135. * @param progress [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown.
  136. * @param result_param2 Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown").
  137. * @param target_system System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
  138. * @param target_component Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
  139. * @return length of the message in bytes (excluding serial stream start sign)
  140. */
  141. static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  142. mavlink_message_t* msg,
  143. uint16_t command,uint8_t result,uint8_t progress,int32_t result_param2,uint8_t target_system,uint8_t target_component)
  144. {
  145. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  146. char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN];
  147. _mav_put_uint16_t(buf, 0, command);
  148. _mav_put_uint8_t(buf, 2, result);
  149. _mav_put_uint8_t(buf, 3, progress);
  150. _mav_put_int32_t(buf, 4, result_param2);
  151. _mav_put_uint8_t(buf, 8, target_system);
  152. _mav_put_uint8_t(buf, 9, target_component);
  153. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
  154. #else
  155. mavlink_command_ack_t packet;
  156. packet.command = command;
  157. packet.result = result;
  158. packet.progress = progress;
  159. packet.result_param2 = result_param2;
  160. packet.target_system = target_system;
  161. packet.target_component = target_component;
  162. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
  163. #endif
  164. msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
  165. 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);
  166. }
  167. /**
  168. * @brief Encode a command_ack struct
  169. *
  170. * @param system_id ID of this system
  171. * @param component_id ID of this component (e.g. 200 for IMU)
  172. * @param msg The MAVLink message to compress the data into
  173. * @param command_ack C-struct to read the message contents from
  174. */
  175. 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)
  176. {
  177. return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result, command_ack->progress, command_ack->result_param2, command_ack->target_system, command_ack->target_component);
  178. }
  179. /**
  180. * @brief Encode a command_ack struct on a channel
  181. *
  182. * @param system_id ID of this system
  183. * @param component_id ID of this component (e.g. 200 for IMU)
  184. * @param chan The MAVLink channel this message will be sent over
  185. * @param msg The MAVLink message to compress the data into
  186. * @param command_ack C-struct to read the message contents from
  187. */
  188. 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)
  189. {
  190. return mavlink_msg_command_ack_pack_chan(system_id, component_id, chan, msg, command_ack->command, command_ack->result, command_ack->progress, command_ack->result_param2, command_ack->target_system, command_ack->target_component);
  191. }
  192. /**
  193. * @brief Encode a command_ack struct with provided status structure
  194. *
  195. * @param system_id ID of this system
  196. * @param component_id ID of this component (e.g. 200 for IMU)
  197. * @param status MAVLink status structure
  198. * @param msg The MAVLink message to compress the data into
  199. * @param command_ack C-struct to read the message contents from
  200. */
  201. static inline uint16_t mavlink_msg_command_ack_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack)
  202. {
  203. return mavlink_msg_command_ack_pack_status(system_id, component_id, _status, msg, command_ack->command, command_ack->result, command_ack->progress, command_ack->result_param2, command_ack->target_system, command_ack->target_component);
  204. }
  205. /**
  206. * @brief Send a command_ack message
  207. * @param chan MAVLink channel to send the message
  208. *
  209. * @param command Command ID (of acknowledged command).
  210. * @param result Result of command.
  211. * @param progress [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown.
  212. * @param result_param2 Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown").
  213. * @param target_system System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
  214. * @param target_component Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
  215. */
  216. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  217. static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result, uint8_t progress, int32_t result_param2, uint8_t target_system, uint8_t target_component)
  218. {
  219. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  220. char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN];
  221. _mav_put_uint16_t(buf, 0, command);
  222. _mav_put_uint8_t(buf, 2, result);
  223. _mav_put_uint8_t(buf, 3, progress);
  224. _mav_put_int32_t(buf, 4, result_param2);
  225. _mav_put_uint8_t(buf, 8, target_system);
  226. _mav_put_uint8_t(buf, 9, target_component);
  227. _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);
  228. #else
  229. mavlink_command_ack_t packet;
  230. packet.command = command;
  231. packet.result = result;
  232. packet.progress = progress;
  233. packet.result_param2 = result_param2;
  234. packet.target_system = target_system;
  235. packet.target_component = target_component;
  236. _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);
  237. #endif
  238. }
  239. /**
  240. * @brief Send a command_ack message
  241. * @param chan MAVLink channel to send the message
  242. * @param struct The MAVLink struct to serialize
  243. */
  244. static inline void mavlink_msg_command_ack_send_struct(mavlink_channel_t chan, const mavlink_command_ack_t* command_ack)
  245. {
  246. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  247. mavlink_msg_command_ack_send(chan, command_ack->command, command_ack->result, command_ack->progress, command_ack->result_param2, command_ack->target_system, command_ack->target_component);
  248. #else
  249. _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);
  250. #endif
  251. }
  252. #if MAVLINK_MSG_ID_COMMAND_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  253. /*
  254. This variant of _send() can be used to save stack space by re-using
  255. memory from the receive buffer. The caller provides a
  256. mavlink_message_t which is the size of a full mavlink message. This
  257. is usually the receive buffer for the channel, and allows a reply to an
  258. incoming message with minimum stack space usage.
  259. */
  260. static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t command, uint8_t result, uint8_t progress, int32_t result_param2, uint8_t target_system, uint8_t target_component)
  261. {
  262. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  263. char *buf = (char *)msgbuf;
  264. _mav_put_uint16_t(buf, 0, command);
  265. _mav_put_uint8_t(buf, 2, result);
  266. _mav_put_uint8_t(buf, 3, progress);
  267. _mav_put_int32_t(buf, 4, result_param2);
  268. _mav_put_uint8_t(buf, 8, target_system);
  269. _mav_put_uint8_t(buf, 9, target_component);
  270. _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);
  271. #else
  272. mavlink_command_ack_t *packet = (mavlink_command_ack_t *)msgbuf;
  273. packet->command = command;
  274. packet->result = result;
  275. packet->progress = progress;
  276. packet->result_param2 = result_param2;
  277. packet->target_system = target_system;
  278. packet->target_component = target_component;
  279. _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);
  280. #endif
  281. }
  282. #endif
  283. #endif
  284. // MESSAGE COMMAND_ACK UNPACKING
  285. /**
  286. * @brief Get field command from command_ack message
  287. *
  288. * @return Command ID (of acknowledged command).
  289. */
  290. static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message_t* msg)
  291. {
  292. return _MAV_RETURN_uint16_t(msg, 0);
  293. }
  294. /**
  295. * @brief Get field result from command_ack message
  296. *
  297. * @return Result of command.
  298. */
  299. static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg)
  300. {
  301. return _MAV_RETURN_uint8_t(msg, 2);
  302. }
  303. /**
  304. * @brief Get field progress from command_ack message
  305. *
  306. * @return [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown.
  307. */
  308. static inline uint8_t mavlink_msg_command_ack_get_progress(const mavlink_message_t* msg)
  309. {
  310. return _MAV_RETURN_uint8_t(msg, 3);
  311. }
  312. /**
  313. * @brief Get field result_param2 from command_ack message
  314. *
  315. * @return Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown").
  316. */
  317. static inline int32_t mavlink_msg_command_ack_get_result_param2(const mavlink_message_t* msg)
  318. {
  319. return _MAV_RETURN_int32_t(msg, 4);
  320. }
  321. /**
  322. * @brief Get field target_system from command_ack message
  323. *
  324. * @return System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
  325. */
  326. static inline uint8_t mavlink_msg_command_ack_get_target_system(const mavlink_message_t* msg)
  327. {
  328. return _MAV_RETURN_uint8_t(msg, 8);
  329. }
  330. /**
  331. * @brief Get field target_component from command_ack message
  332. *
  333. * @return Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
  334. */
  335. static inline uint8_t mavlink_msg_command_ack_get_target_component(const mavlink_message_t* msg)
  336. {
  337. return _MAV_RETURN_uint8_t(msg, 9);
  338. }
  339. /**
  340. * @brief Decode a command_ack message into a struct
  341. *
  342. * @param msg The message to decode
  343. * @param command_ack C-struct to decode the message contents into
  344. */
  345. static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack)
  346. {
  347. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  348. command_ack->command = mavlink_msg_command_ack_get_command(msg);
  349. command_ack->result = mavlink_msg_command_ack_get_result(msg);
  350. command_ack->progress = mavlink_msg_command_ack_get_progress(msg);
  351. command_ack->result_param2 = mavlink_msg_command_ack_get_result_param2(msg);
  352. command_ack->target_system = mavlink_msg_command_ack_get_target_system(msg);
  353. command_ack->target_component = mavlink_msg_command_ack_get_target_component(msg);
  354. #else
  355. uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_ACK_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_ACK_LEN;
  356. memset(command_ack, 0, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
  357. memcpy(command_ack, _MAV_PAYLOAD(msg), len);
  358. #endif
  359. }