mavlink_msg_mission_current.h 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363
  1. #pragma once
  2. // MESSAGE MISSION_CURRENT PACKING
  3. #define MAVLINK_MSG_ID_MISSION_CURRENT 42
  4. MAVPACKED(
  5. typedef struct __mavlink_mission_current_t {
  6. uint16_t seq; /*< Sequence*/
  7. uint16_t total; /*< Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.*/
  8. uint8_t mission_state; /*< Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.*/
  9. uint8_t mission_mode; /*< Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).*/
  10. uint32_t mission_id; /*< Id of current on-vehicle mission plan, or 0 if IDs are not supported or there is no mission loaded. GCS can use this to track changes to the mission plan type. The same value is returned on mission upload (in the MISSION_ACK).*/
  11. uint32_t fence_id; /*< Id of current on-vehicle fence plan, or 0 if IDs are not supported or there is no fence loaded. GCS can use this to track changes to the fence plan type. The same value is returned on fence upload (in the MISSION_ACK).*/
  12. uint32_t rally_points_id; /*< Id of current on-vehicle rally point plan, or 0 if IDs are not supported or there are no rally points loaded. GCS can use this to track changes to the rally point plan type. The same value is returned on rally point upload (in the MISSION_ACK).*/
  13. }) mavlink_mission_current_t;
  14. #define MAVLINK_MSG_ID_MISSION_CURRENT_LEN 18
  15. #define MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN 2
  16. #define MAVLINK_MSG_ID_42_LEN 18
  17. #define MAVLINK_MSG_ID_42_MIN_LEN 2
  18. #define MAVLINK_MSG_ID_MISSION_CURRENT_CRC 28
  19. #define MAVLINK_MSG_ID_42_CRC 28
  20. #if MAVLINK_COMMAND_24BIT
  21. #define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \
  22. 42, \
  23. "MISSION_CURRENT", \
  24. 7, \
  25. { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \
  26. { "total", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_mission_current_t, total) }, \
  27. { "mission_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_current_t, mission_state) }, \
  28. { "mission_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_current_t, mission_mode) }, \
  29. { "mission_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 6, offsetof(mavlink_mission_current_t, mission_id) }, \
  30. { "fence_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 10, offsetof(mavlink_mission_current_t, fence_id) }, \
  31. { "rally_points_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 14, offsetof(mavlink_mission_current_t, rally_points_id) }, \
  32. } \
  33. }
  34. #else
  35. #define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \
  36. "MISSION_CURRENT", \
  37. 7, \
  38. { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \
  39. { "total", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_mission_current_t, total) }, \
  40. { "mission_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_current_t, mission_state) }, \
  41. { "mission_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_current_t, mission_mode) }, \
  42. { "mission_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 6, offsetof(mavlink_mission_current_t, mission_id) }, \
  43. { "fence_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 10, offsetof(mavlink_mission_current_t, fence_id) }, \
  44. { "rally_points_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 14, offsetof(mavlink_mission_current_t, rally_points_id) }, \
  45. } \
  46. }
  47. #endif
  48. /**
  49. * @brief Pack a mission_current 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 seq Sequence
  55. * @param total Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.
  56. * @param mission_state Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.
  57. * @param mission_mode Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).
  58. * @param mission_id Id of current on-vehicle mission plan, or 0 if IDs are not supported or there is no mission loaded. GCS can use this to track changes to the mission plan type. The same value is returned on mission upload (in the MISSION_ACK).
  59. * @param fence_id Id of current on-vehicle fence plan, or 0 if IDs are not supported or there is no fence loaded. GCS can use this to track changes to the fence plan type. The same value is returned on fence upload (in the MISSION_ACK).
  60. * @param rally_points_id Id of current on-vehicle rally point plan, or 0 if IDs are not supported or there are no rally points loaded. GCS can use this to track changes to the rally point plan type. The same value is returned on rally point upload (in the MISSION_ACK).
  61. * @return length of the message in bytes (excluding serial stream start sign)
  62. */
  63. static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  64. uint16_t seq, uint16_t total, uint8_t mission_state, uint8_t mission_mode, uint32_t mission_id, uint32_t fence_id, uint32_t rally_points_id)
  65. {
  66. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  67. char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN];
  68. _mav_put_uint16_t(buf, 0, seq);
  69. _mav_put_uint16_t(buf, 2, total);
  70. _mav_put_uint8_t(buf, 4, mission_state);
  71. _mav_put_uint8_t(buf, 5, mission_mode);
  72. _mav_put_uint32_t(buf, 6, mission_id);
  73. _mav_put_uint32_t(buf, 10, fence_id);
  74. _mav_put_uint32_t(buf, 14, rally_points_id);
  75. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
  76. #else
  77. mavlink_mission_current_t packet;
  78. packet.seq = seq;
  79. packet.total = total;
  80. packet.mission_state = mission_state;
  81. packet.mission_mode = mission_mode;
  82. packet.mission_id = mission_id;
  83. packet.fence_id = fence_id;
  84. packet.rally_points_id = rally_points_id;
  85. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
  86. #endif
  87. msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT;
  88. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
  89. }
  90. /**
  91. * @brief Pack a mission_current message on a channel
  92. * @param system_id ID of this system
  93. * @param component_id ID of this component (e.g. 200 for IMU)
  94. * @param chan The MAVLink channel this message will be sent over
  95. * @param msg The MAVLink message to compress the data into
  96. * @param seq Sequence
  97. * @param total Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.
  98. * @param mission_state Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.
  99. * @param mission_mode Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).
  100. * @param mission_id Id of current on-vehicle mission plan, or 0 if IDs are not supported or there is no mission loaded. GCS can use this to track changes to the mission plan type. The same value is returned on mission upload (in the MISSION_ACK).
  101. * @param fence_id Id of current on-vehicle fence plan, or 0 if IDs are not supported or there is no fence loaded. GCS can use this to track changes to the fence plan type. The same value is returned on fence upload (in the MISSION_ACK).
  102. * @param rally_points_id Id of current on-vehicle rally point plan, or 0 if IDs are not supported or there are no rally points loaded. GCS can use this to track changes to the rally point plan type. The same value is returned on rally point upload (in the MISSION_ACK).
  103. * @return length of the message in bytes (excluding serial stream start sign)
  104. */
  105. static inline uint16_t mavlink_msg_mission_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  106. mavlink_message_t* msg,
  107. uint16_t seq,uint16_t total,uint8_t mission_state,uint8_t mission_mode,uint32_t mission_id,uint32_t fence_id,uint32_t rally_points_id)
  108. {
  109. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  110. char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN];
  111. _mav_put_uint16_t(buf, 0, seq);
  112. _mav_put_uint16_t(buf, 2, total);
  113. _mav_put_uint8_t(buf, 4, mission_state);
  114. _mav_put_uint8_t(buf, 5, mission_mode);
  115. _mav_put_uint32_t(buf, 6, mission_id);
  116. _mav_put_uint32_t(buf, 10, fence_id);
  117. _mav_put_uint32_t(buf, 14, rally_points_id);
  118. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
  119. #else
  120. mavlink_mission_current_t packet;
  121. packet.seq = seq;
  122. packet.total = total;
  123. packet.mission_state = mission_state;
  124. packet.mission_mode = mission_mode;
  125. packet.mission_id = mission_id;
  126. packet.fence_id = fence_id;
  127. packet.rally_points_id = rally_points_id;
  128. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
  129. #endif
  130. msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT;
  131. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
  132. }
  133. /**
  134. * @brief Encode a mission_current struct
  135. *
  136. * @param system_id ID of this system
  137. * @param component_id ID of this component (e.g. 200 for IMU)
  138. * @param msg The MAVLink message to compress the data into
  139. * @param mission_current C-struct to read the message contents from
  140. */
  141. static inline uint16_t mavlink_msg_mission_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current)
  142. {
  143. return mavlink_msg_mission_current_pack(system_id, component_id, msg, mission_current->seq, mission_current->total, mission_current->mission_state, mission_current->mission_mode, mission_current->mission_id, mission_current->fence_id, mission_current->rally_points_id);
  144. }
  145. /**
  146. * @brief Encode a mission_current struct on a channel
  147. *
  148. * @param system_id ID of this system
  149. * @param component_id ID of this component (e.g. 200 for IMU)
  150. * @param chan The MAVLink channel this message will be sent over
  151. * @param msg The MAVLink message to compress the data into
  152. * @param mission_current C-struct to read the message contents from
  153. */
  154. static inline uint16_t mavlink_msg_mission_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current)
  155. {
  156. return mavlink_msg_mission_current_pack_chan(system_id, component_id, chan, msg, mission_current->seq, mission_current->total, mission_current->mission_state, mission_current->mission_mode, mission_current->mission_id, mission_current->fence_id, mission_current->rally_points_id);
  157. }
  158. /**
  159. * @brief Send a mission_current message
  160. * @param chan MAVLink channel to send the message
  161. *
  162. * @param seq Sequence
  163. * @param total Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.
  164. * @param mission_state Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.
  165. * @param mission_mode Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).
  166. * @param mission_id Id of current on-vehicle mission plan, or 0 if IDs are not supported or there is no mission loaded. GCS can use this to track changes to the mission plan type. The same value is returned on mission upload (in the MISSION_ACK).
  167. * @param fence_id Id of current on-vehicle fence plan, or 0 if IDs are not supported or there is no fence loaded. GCS can use this to track changes to the fence plan type. The same value is returned on fence upload (in the MISSION_ACK).
  168. * @param rally_points_id Id of current on-vehicle rally point plan, or 0 if IDs are not supported or there are no rally points loaded. GCS can use this to track changes to the rally point plan type. The same value is returned on rally point upload (in the MISSION_ACK).
  169. */
  170. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  171. static inline void mavlink_msg_mission_current_send(mavlink_channel_t chan, uint16_t seq, uint16_t total, uint8_t mission_state, uint8_t mission_mode, uint32_t mission_id, uint32_t fence_id, uint32_t rally_points_id)
  172. {
  173. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  174. char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN];
  175. _mav_put_uint16_t(buf, 0, seq);
  176. _mav_put_uint16_t(buf, 2, total);
  177. _mav_put_uint8_t(buf, 4, mission_state);
  178. _mav_put_uint8_t(buf, 5, mission_mode);
  179. _mav_put_uint32_t(buf, 6, mission_id);
  180. _mav_put_uint32_t(buf, 10, fence_id);
  181. _mav_put_uint32_t(buf, 14, rally_points_id);
  182. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
  183. #else
  184. mavlink_mission_current_t packet;
  185. packet.seq = seq;
  186. packet.total = total;
  187. packet.mission_state = mission_state;
  188. packet.mission_mode = mission_mode;
  189. packet.mission_id = mission_id;
  190. packet.fence_id = fence_id;
  191. packet.rally_points_id = rally_points_id;
  192. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
  193. #endif
  194. }
  195. /**
  196. * @brief Send a mission_current message
  197. * @param chan MAVLink channel to send the message
  198. * @param struct The MAVLink struct to serialize
  199. */
  200. static inline void mavlink_msg_mission_current_send_struct(mavlink_channel_t chan, const mavlink_mission_current_t* mission_current)
  201. {
  202. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  203. mavlink_msg_mission_current_send(chan, mission_current->seq, mission_current->total, mission_current->mission_state, mission_current->mission_mode, mission_current->mission_id, mission_current->fence_id, mission_current->rally_points_id);
  204. #else
  205. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)mission_current, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
  206. #endif
  207. }
  208. #if MAVLINK_MSG_ID_MISSION_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  209. /*
  210. This variant of _send() can be used to save stack space by re-using
  211. memory from the receive buffer. The caller provides a
  212. mavlink_message_t which is the size of a full mavlink message. This
  213. is usually the receive buffer for the channel, and allows a reply to an
  214. incoming message with minimum stack space usage.
  215. */
  216. static inline void mavlink_msg_mission_current_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq, uint16_t total, uint8_t mission_state, uint8_t mission_mode, uint32_t mission_id, uint32_t fence_id, uint32_t rally_points_id)
  217. {
  218. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  219. char *buf = (char *)msgbuf;
  220. _mav_put_uint16_t(buf, 0, seq);
  221. _mav_put_uint16_t(buf, 2, total);
  222. _mav_put_uint8_t(buf, 4, mission_state);
  223. _mav_put_uint8_t(buf, 5, mission_mode);
  224. _mav_put_uint32_t(buf, 6, mission_id);
  225. _mav_put_uint32_t(buf, 10, fence_id);
  226. _mav_put_uint32_t(buf, 14, rally_points_id);
  227. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
  228. #else
  229. mavlink_mission_current_t *packet = (mavlink_mission_current_t *)msgbuf;
  230. packet->seq = seq;
  231. packet->total = total;
  232. packet->mission_state = mission_state;
  233. packet->mission_mode = mission_mode;
  234. packet->mission_id = mission_id;
  235. packet->fence_id = fence_id;
  236. packet->rally_points_id = rally_points_id;
  237. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
  238. #endif
  239. }
  240. #endif
  241. #endif
  242. // MESSAGE MISSION_CURRENT UNPACKING
  243. /**
  244. * @brief Get field seq from mission_current message
  245. *
  246. * @return Sequence
  247. */
  248. static inline uint16_t mavlink_msg_mission_current_get_seq(const mavlink_message_t* msg)
  249. {
  250. return _MAV_RETURN_uint16_t(msg, 0);
  251. }
  252. /**
  253. * @brief Get field total from mission_current message
  254. *
  255. * @return Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.
  256. */
  257. static inline uint16_t mavlink_msg_mission_current_get_total(const mavlink_message_t* msg)
  258. {
  259. return _MAV_RETURN_uint16_t(msg, 2);
  260. }
  261. /**
  262. * @brief Get field mission_state from mission_current message
  263. *
  264. * @return Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.
  265. */
  266. static inline uint8_t mavlink_msg_mission_current_get_mission_state(const mavlink_message_t* msg)
  267. {
  268. return _MAV_RETURN_uint8_t(msg, 4);
  269. }
  270. /**
  271. * @brief Get field mission_mode from mission_current message
  272. *
  273. * @return Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).
  274. */
  275. static inline uint8_t mavlink_msg_mission_current_get_mission_mode(const mavlink_message_t* msg)
  276. {
  277. return _MAV_RETURN_uint8_t(msg, 5);
  278. }
  279. /**
  280. * @brief Get field mission_id from mission_current message
  281. *
  282. * @return Id of current on-vehicle mission plan, or 0 if IDs are not supported or there is no mission loaded. GCS can use this to track changes to the mission plan type. The same value is returned on mission upload (in the MISSION_ACK).
  283. */
  284. static inline uint32_t mavlink_msg_mission_current_get_mission_id(const mavlink_message_t* msg)
  285. {
  286. return _MAV_RETURN_uint32_t(msg, 6);
  287. }
  288. /**
  289. * @brief Get field fence_id from mission_current message
  290. *
  291. * @return Id of current on-vehicle fence plan, or 0 if IDs are not supported or there is no fence loaded. GCS can use this to track changes to the fence plan type. The same value is returned on fence upload (in the MISSION_ACK).
  292. */
  293. static inline uint32_t mavlink_msg_mission_current_get_fence_id(const mavlink_message_t* msg)
  294. {
  295. return _MAV_RETURN_uint32_t(msg, 10);
  296. }
  297. /**
  298. * @brief Get field rally_points_id from mission_current message
  299. *
  300. * @return Id of current on-vehicle rally point plan, or 0 if IDs are not supported or there are no rally points loaded. GCS can use this to track changes to the rally point plan type. The same value is returned on rally point upload (in the MISSION_ACK).
  301. */
  302. static inline uint32_t mavlink_msg_mission_current_get_rally_points_id(const mavlink_message_t* msg)
  303. {
  304. return _MAV_RETURN_uint32_t(msg, 14);
  305. }
  306. /**
  307. * @brief Decode a mission_current message into a struct
  308. *
  309. * @param msg The message to decode
  310. * @param mission_current C-struct to decode the message contents into
  311. */
  312. static inline void mavlink_msg_mission_current_decode(const mavlink_message_t* msg, mavlink_mission_current_t* mission_current)
  313. {
  314. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  315. mission_current->seq = mavlink_msg_mission_current_get_seq(msg);
  316. mission_current->total = mavlink_msg_mission_current_get_total(msg);
  317. mission_current->mission_state = mavlink_msg_mission_current_get_mission_state(msg);
  318. mission_current->mission_mode = mavlink_msg_mission_current_get_mission_mode(msg);
  319. mission_current->mission_id = mavlink_msg_mission_current_get_mission_id(msg);
  320. mission_current->fence_id = mavlink_msg_mission_current_get_fence_id(msg);
  321. mission_current->rally_points_id = mavlink_msg_mission_current_get_rally_points_id(msg);
  322. #else
  323. uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_CURRENT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_CURRENT_LEN;
  324. memset(mission_current, 0, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
  325. memcpy(mission_current, _MAV_PAYLOAD(msg), len);
  326. #endif
  327. }