mavlink_msg_mission_count.h 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408
  1. #pragma once
  2. // MESSAGE MISSION_COUNT PACKING
  3. #define MAVLINK_MSG_ID_MISSION_COUNT 44
  4. MAVPACKED(
  5. typedef struct __mavlink_mission_count_t {
  6. uint16_t count; /*< Number of mission items in the sequence*/
  7. uint8_t target_system; /*< System ID*/
  8. uint8_t target_component; /*< Component ID*/
  9. uint8_t mission_type; /*< Mission type.*/
  10. uint32_t opaque_id; /*< Id of current on-vehicle mission, fence, or rally point plan (on download from vehicle).
  11. This field is used when downloading a plan from a vehicle to a GCS.
  12. 0 on upload to the vehicle from GCS.
  13. 0 if plan ids are not supported.
  14. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded.
  15. The ids are recalculated by the vehicle when any part of the on-vehicle plan changes (when a new plan is uploaded, the vehicle returns the new id to the GCS in MISSION_ACK).
  16. */
  17. }) mavlink_mission_count_t;
  18. #define MAVLINK_MSG_ID_MISSION_COUNT_LEN 9
  19. #define MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN 4
  20. #define MAVLINK_MSG_ID_44_LEN 9
  21. #define MAVLINK_MSG_ID_44_MIN_LEN 4
  22. #define MAVLINK_MSG_ID_MISSION_COUNT_CRC 221
  23. #define MAVLINK_MSG_ID_44_CRC 221
  24. #if MAVLINK_COMMAND_24BIT
  25. #define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \
  26. 44, \
  27. "MISSION_COUNT", \
  28. 5, \
  29. { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \
  30. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \
  31. { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \
  32. { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_count_t, mission_type) }, \
  33. { "opaque_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 5, offsetof(mavlink_mission_count_t, opaque_id) }, \
  34. } \
  35. }
  36. #else
  37. #define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \
  38. "MISSION_COUNT", \
  39. 5, \
  40. { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \
  41. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \
  42. { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \
  43. { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_count_t, mission_type) }, \
  44. { "opaque_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 5, offsetof(mavlink_mission_count_t, opaque_id) }, \
  45. } \
  46. }
  47. #endif
  48. /**
  49. * @brief Pack a mission_count message
  50. * @param system_id ID of this system
  51. * @param component_id ID of this component (e.g. 200 for IMU)
  52. * @param msg The MAVLink message to compress the data into
  53. *
  54. * @param target_system System ID
  55. * @param target_component Component ID
  56. * @param count Number of mission items in the sequence
  57. * @param mission_type Mission type.
  58. * @param opaque_id Id of current on-vehicle mission, fence, or rally point plan (on download from vehicle).
  59. This field is used when downloading a plan from a vehicle to a GCS.
  60. 0 on upload to the vehicle from GCS.
  61. 0 if plan ids are not supported.
  62. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded.
  63. The ids are recalculated by the vehicle when any part of the on-vehicle plan changes (when a new plan is uploaded, the vehicle returns the new id to the GCS in MISSION_ACK).
  64. * @return length of the message in bytes (excluding serial stream start sign)
  65. */
  66. static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  67. uint8_t target_system, uint8_t target_component, uint16_t count, uint8_t mission_type, uint32_t opaque_id)
  68. {
  69. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  70. char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN];
  71. _mav_put_uint16_t(buf, 0, count);
  72. _mav_put_uint8_t(buf, 2, target_system);
  73. _mav_put_uint8_t(buf, 3, target_component);
  74. _mav_put_uint8_t(buf, 4, mission_type);
  75. _mav_put_uint32_t(buf, 5, opaque_id);
  76. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
  77. #else
  78. mavlink_mission_count_t packet;
  79. packet.count = count;
  80. packet.target_system = target_system;
  81. packet.target_component = target_component;
  82. packet.mission_type = mission_type;
  83. packet.opaque_id = opaque_id;
  84. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
  85. #endif
  86. msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT;
  87. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
  88. }
  89. /**
  90. * @brief Pack a mission_count message
  91. * @param system_id ID of this system
  92. * @param component_id ID of this component (e.g. 200 for IMU)
  93. * @param status MAVLink status structure
  94. * @param msg The MAVLink message to compress the data into
  95. *
  96. * @param target_system System ID
  97. * @param target_component Component ID
  98. * @param count Number of mission items in the sequence
  99. * @param mission_type Mission type.
  100. * @param opaque_id Id of current on-vehicle mission, fence, or rally point plan (on download from vehicle).
  101. This field is used when downloading a plan from a vehicle to a GCS.
  102. 0 on upload to the vehicle from GCS.
  103. 0 if plan ids are not supported.
  104. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded.
  105. The ids are recalculated by the vehicle when any part of the on-vehicle plan changes (when a new plan is uploaded, the vehicle returns the new id to the GCS in MISSION_ACK).
  106. * @return length of the message in bytes (excluding serial stream start sign)
  107. */
  108. static inline uint16_t mavlink_msg_mission_count_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  109. uint8_t target_system, uint8_t target_component, uint16_t count, uint8_t mission_type, uint32_t opaque_id)
  110. {
  111. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  112. char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN];
  113. _mav_put_uint16_t(buf, 0, count);
  114. _mav_put_uint8_t(buf, 2, target_system);
  115. _mav_put_uint8_t(buf, 3, target_component);
  116. _mav_put_uint8_t(buf, 4, mission_type);
  117. _mav_put_uint32_t(buf, 5, opaque_id);
  118. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
  119. #else
  120. mavlink_mission_count_t packet;
  121. packet.count = count;
  122. packet.target_system = target_system;
  123. packet.target_component = target_component;
  124. packet.mission_type = mission_type;
  125. packet.opaque_id = opaque_id;
  126. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
  127. #endif
  128. msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT;
  129. #if MAVLINK_CRC_EXTRA
  130. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
  131. #else
  132. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
  133. #endif
  134. }
  135. /**
  136. * @brief Pack a mission_count message on a channel
  137. * @param system_id ID of this system
  138. * @param component_id ID of this component (e.g. 200 for IMU)
  139. * @param chan The MAVLink channel this message will be sent over
  140. * @param msg The MAVLink message to compress the data into
  141. * @param target_system System ID
  142. * @param target_component Component ID
  143. * @param count Number of mission items in the sequence
  144. * @param mission_type Mission type.
  145. * @param opaque_id Id of current on-vehicle mission, fence, or rally point plan (on download from vehicle).
  146. This field is used when downloading a plan from a vehicle to a GCS.
  147. 0 on upload to the vehicle from GCS.
  148. 0 if plan ids are not supported.
  149. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded.
  150. The ids are recalculated by the vehicle when any part of the on-vehicle plan changes (when a new plan is uploaded, the vehicle returns the new id to the GCS in MISSION_ACK).
  151. * @return length of the message in bytes (excluding serial stream start sign)
  152. */
  153. static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  154. mavlink_message_t* msg,
  155. uint8_t target_system,uint8_t target_component,uint16_t count,uint8_t mission_type,uint32_t opaque_id)
  156. {
  157. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  158. char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN];
  159. _mav_put_uint16_t(buf, 0, count);
  160. _mav_put_uint8_t(buf, 2, target_system);
  161. _mav_put_uint8_t(buf, 3, target_component);
  162. _mav_put_uint8_t(buf, 4, mission_type);
  163. _mav_put_uint32_t(buf, 5, opaque_id);
  164. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
  165. #else
  166. mavlink_mission_count_t packet;
  167. packet.count = count;
  168. packet.target_system = target_system;
  169. packet.target_component = target_component;
  170. packet.mission_type = mission_type;
  171. packet.opaque_id = opaque_id;
  172. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
  173. #endif
  174. msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT;
  175. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
  176. }
  177. /**
  178. * @brief Encode a mission_count struct
  179. *
  180. * @param system_id ID of this system
  181. * @param component_id ID of this component (e.g. 200 for IMU)
  182. * @param msg The MAVLink message to compress the data into
  183. * @param mission_count C-struct to read the message contents from
  184. */
  185. static inline uint16_t mavlink_msg_mission_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count)
  186. {
  187. return mavlink_msg_mission_count_pack(system_id, component_id, msg, mission_count->target_system, mission_count->target_component, mission_count->count, mission_count->mission_type, mission_count->opaque_id);
  188. }
  189. /**
  190. * @brief Encode a mission_count struct on a channel
  191. *
  192. * @param system_id ID of this system
  193. * @param component_id ID of this component (e.g. 200 for IMU)
  194. * @param chan The MAVLink channel this message will be sent over
  195. * @param msg The MAVLink message to compress the data into
  196. * @param mission_count C-struct to read the message contents from
  197. */
  198. static inline uint16_t mavlink_msg_mission_count_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count)
  199. {
  200. return mavlink_msg_mission_count_pack_chan(system_id, component_id, chan, msg, mission_count->target_system, mission_count->target_component, mission_count->count, mission_count->mission_type, mission_count->opaque_id);
  201. }
  202. /**
  203. * @brief Encode a mission_count struct with provided status structure
  204. *
  205. * @param system_id ID of this system
  206. * @param component_id ID of this component (e.g. 200 for IMU)
  207. * @param status MAVLink status structure
  208. * @param msg The MAVLink message to compress the data into
  209. * @param mission_count C-struct to read the message contents from
  210. */
  211. static inline uint16_t mavlink_msg_mission_count_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count)
  212. {
  213. return mavlink_msg_mission_count_pack_status(system_id, component_id, _status, msg, mission_count->target_system, mission_count->target_component, mission_count->count, mission_count->mission_type, mission_count->opaque_id);
  214. }
  215. /**
  216. * @brief Send a mission_count message
  217. * @param chan MAVLink channel to send the message
  218. *
  219. * @param target_system System ID
  220. * @param target_component Component ID
  221. * @param count Number of mission items in the sequence
  222. * @param mission_type Mission type.
  223. * @param opaque_id Id of current on-vehicle mission, fence, or rally point plan (on download from vehicle).
  224. This field is used when downloading a plan from a vehicle to a GCS.
  225. 0 on upload to the vehicle from GCS.
  226. 0 if plan ids are not supported.
  227. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded.
  228. The ids are recalculated by the vehicle when any part of the on-vehicle plan changes (when a new plan is uploaded, the vehicle returns the new id to the GCS in MISSION_ACK).
  229. */
  230. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  231. static inline void mavlink_msg_mission_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count, uint8_t mission_type, uint32_t opaque_id)
  232. {
  233. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  234. char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN];
  235. _mav_put_uint16_t(buf, 0, count);
  236. _mav_put_uint8_t(buf, 2, target_system);
  237. _mav_put_uint8_t(buf, 3, target_component);
  238. _mav_put_uint8_t(buf, 4, mission_type);
  239. _mav_put_uint32_t(buf, 5, opaque_id);
  240. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
  241. #else
  242. mavlink_mission_count_t packet;
  243. packet.count = count;
  244. packet.target_system = target_system;
  245. packet.target_component = target_component;
  246. packet.mission_type = mission_type;
  247. packet.opaque_id = opaque_id;
  248. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
  249. #endif
  250. }
  251. /**
  252. * @brief Send a mission_count message
  253. * @param chan MAVLink channel to send the message
  254. * @param struct The MAVLink struct to serialize
  255. */
  256. static inline void mavlink_msg_mission_count_send_struct(mavlink_channel_t chan, const mavlink_mission_count_t* mission_count)
  257. {
  258. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  259. mavlink_msg_mission_count_send(chan, mission_count->target_system, mission_count->target_component, mission_count->count, mission_count->mission_type, mission_count->opaque_id);
  260. #else
  261. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)mission_count, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
  262. #endif
  263. }
  264. #if MAVLINK_MSG_ID_MISSION_COUNT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  265. /*
  266. This variant of _send() can be used to save stack space by re-using
  267. memory from the receive buffer. The caller provides a
  268. mavlink_message_t which is the size of a full mavlink message. This
  269. is usually the receive buffer for the channel, and allows a reply to an
  270. incoming message with minimum stack space usage.
  271. */
  272. static inline void mavlink_msg_mission_count_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count, uint8_t mission_type, uint32_t opaque_id)
  273. {
  274. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  275. char *buf = (char *)msgbuf;
  276. _mav_put_uint16_t(buf, 0, count);
  277. _mav_put_uint8_t(buf, 2, target_system);
  278. _mav_put_uint8_t(buf, 3, target_component);
  279. _mav_put_uint8_t(buf, 4, mission_type);
  280. _mav_put_uint32_t(buf, 5, opaque_id);
  281. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
  282. #else
  283. mavlink_mission_count_t *packet = (mavlink_mission_count_t *)msgbuf;
  284. packet->count = count;
  285. packet->target_system = target_system;
  286. packet->target_component = target_component;
  287. packet->mission_type = mission_type;
  288. packet->opaque_id = opaque_id;
  289. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)packet, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
  290. #endif
  291. }
  292. #endif
  293. #endif
  294. // MESSAGE MISSION_COUNT UNPACKING
  295. /**
  296. * @brief Get field target_system from mission_count message
  297. *
  298. * @return System ID
  299. */
  300. static inline uint8_t mavlink_msg_mission_count_get_target_system(const mavlink_message_t* msg)
  301. {
  302. return _MAV_RETURN_uint8_t(msg, 2);
  303. }
  304. /**
  305. * @brief Get field target_component from mission_count message
  306. *
  307. * @return Component ID
  308. */
  309. static inline uint8_t mavlink_msg_mission_count_get_target_component(const mavlink_message_t* msg)
  310. {
  311. return _MAV_RETURN_uint8_t(msg, 3);
  312. }
  313. /**
  314. * @brief Get field count from mission_count message
  315. *
  316. * @return Number of mission items in the sequence
  317. */
  318. static inline uint16_t mavlink_msg_mission_count_get_count(const mavlink_message_t* msg)
  319. {
  320. return _MAV_RETURN_uint16_t(msg, 0);
  321. }
  322. /**
  323. * @brief Get field mission_type from mission_count message
  324. *
  325. * @return Mission type.
  326. */
  327. static inline uint8_t mavlink_msg_mission_count_get_mission_type(const mavlink_message_t* msg)
  328. {
  329. return _MAV_RETURN_uint8_t(msg, 4);
  330. }
  331. /**
  332. * @brief Get field opaque_id from mission_count message
  333. *
  334. * @return Id of current on-vehicle mission, fence, or rally point plan (on download from vehicle).
  335. This field is used when downloading a plan from a vehicle to a GCS.
  336. 0 on upload to the vehicle from GCS.
  337. 0 if plan ids are not supported.
  338. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded.
  339. The ids are recalculated by the vehicle when any part of the on-vehicle plan changes (when a new plan is uploaded, the vehicle returns the new id to the GCS in MISSION_ACK).
  340. */
  341. static inline uint32_t mavlink_msg_mission_count_get_opaque_id(const mavlink_message_t* msg)
  342. {
  343. return _MAV_RETURN_uint32_t(msg, 5);
  344. }
  345. /**
  346. * @brief Decode a mission_count message into a struct
  347. *
  348. * @param msg The message to decode
  349. * @param mission_count C-struct to decode the message contents into
  350. */
  351. static inline void mavlink_msg_mission_count_decode(const mavlink_message_t* msg, mavlink_mission_count_t* mission_count)
  352. {
  353. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  354. mission_count->count = mavlink_msg_mission_count_get_count(msg);
  355. mission_count->target_system = mavlink_msg_mission_count_get_target_system(msg);
  356. mission_count->target_component = mavlink_msg_mission_count_get_target_component(msg);
  357. mission_count->mission_type = mavlink_msg_mission_count_get_mission_type(msg);
  358. mission_count->opaque_id = mavlink_msg_mission_count_get_opaque_id(msg);
  359. #else
  360. uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_COUNT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_COUNT_LEN;
  361. memset(mission_count, 0, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
  362. memcpy(mission_count, _MAV_PAYLOAD(msg), len);
  363. #endif
  364. }