2
0

mavlink_msg_mission_current.h 24 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428
  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
  92. * @param system_id ID of this system
  93. * @param component_id ID of this component (e.g. 200 for IMU)
  94. * @param status MAVLink status structure
  95. * @param msg The MAVLink message to compress the data into
  96. *
  97. * @param seq Sequence
  98. * @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.
  99. * @param mission_state Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.
  100. * @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).
  101. * @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).
  102. * @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).
  103. * @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).
  104. * @return length of the message in bytes (excluding serial stream start sign)
  105. */
  106. static inline uint16_t mavlink_msg_mission_current_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, 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. #if MAVLINK_CRC_EXTRA
  132. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
  133. #else
  134. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
  135. #endif
  136. }
  137. /**
  138. * @brief Pack a mission_current message on a channel
  139. * @param system_id ID of this system
  140. * @param component_id ID of this component (e.g. 200 for IMU)
  141. * @param chan The MAVLink channel this message will be sent over
  142. * @param msg The MAVLink message to compress the data into
  143. * @param seq Sequence
  144. * @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.
  145. * @param mission_state Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.
  146. * @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).
  147. * @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).
  148. * @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).
  149. * @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).
  150. * @return length of the message in bytes (excluding serial stream start sign)
  151. */
  152. static inline uint16_t mavlink_msg_mission_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  153. mavlink_message_t* msg,
  154. 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)
  155. {
  156. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  157. char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN];
  158. _mav_put_uint16_t(buf, 0, seq);
  159. _mav_put_uint16_t(buf, 2, total);
  160. _mav_put_uint8_t(buf, 4, mission_state);
  161. _mav_put_uint8_t(buf, 5, mission_mode);
  162. _mav_put_uint32_t(buf, 6, mission_id);
  163. _mav_put_uint32_t(buf, 10, fence_id);
  164. _mav_put_uint32_t(buf, 14, rally_points_id);
  165. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
  166. #else
  167. mavlink_mission_current_t packet;
  168. packet.seq = seq;
  169. packet.total = total;
  170. packet.mission_state = mission_state;
  171. packet.mission_mode = mission_mode;
  172. packet.mission_id = mission_id;
  173. packet.fence_id = fence_id;
  174. packet.rally_points_id = rally_points_id;
  175. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
  176. #endif
  177. msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT;
  178. 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);
  179. }
  180. /**
  181. * @brief Encode a mission_current struct
  182. *
  183. * @param system_id ID of this system
  184. * @param component_id ID of this component (e.g. 200 for IMU)
  185. * @param msg The MAVLink message to compress the data into
  186. * @param mission_current C-struct to read the message contents from
  187. */
  188. 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)
  189. {
  190. 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);
  191. }
  192. /**
  193. * @brief Encode a mission_current struct on a channel
  194. *
  195. * @param system_id ID of this system
  196. * @param component_id ID of this component (e.g. 200 for IMU)
  197. * @param chan The MAVLink channel this message will be sent over
  198. * @param msg The MAVLink message to compress the data into
  199. * @param mission_current C-struct to read the message contents from
  200. */
  201. 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)
  202. {
  203. 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);
  204. }
  205. /**
  206. * @brief Encode a mission_current struct with provided status structure
  207. *
  208. * @param system_id ID of this system
  209. * @param component_id ID of this component (e.g. 200 for IMU)
  210. * @param status MAVLink status structure
  211. * @param msg The MAVLink message to compress the data into
  212. * @param mission_current C-struct to read the message contents from
  213. */
  214. static inline uint16_t mavlink_msg_mission_current_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current)
  215. {
  216. return mavlink_msg_mission_current_pack_status(system_id, component_id, _status, 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);
  217. }
  218. /**
  219. * @brief Send a mission_current message
  220. * @param chan MAVLink channel to send the message
  221. *
  222. * @param seq Sequence
  223. * @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.
  224. * @param mission_state Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.
  225. * @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).
  226. * @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).
  227. * @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).
  228. * @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).
  229. */
  230. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  231. 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)
  232. {
  233. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  234. char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN];
  235. _mav_put_uint16_t(buf, 0, seq);
  236. _mav_put_uint16_t(buf, 2, total);
  237. _mav_put_uint8_t(buf, 4, mission_state);
  238. _mav_put_uint8_t(buf, 5, mission_mode);
  239. _mav_put_uint32_t(buf, 6, mission_id);
  240. _mav_put_uint32_t(buf, 10, fence_id);
  241. _mav_put_uint32_t(buf, 14, rally_points_id);
  242. _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);
  243. #else
  244. mavlink_mission_current_t packet;
  245. packet.seq = seq;
  246. packet.total = total;
  247. packet.mission_state = mission_state;
  248. packet.mission_mode = mission_mode;
  249. packet.mission_id = mission_id;
  250. packet.fence_id = fence_id;
  251. packet.rally_points_id = rally_points_id;
  252. _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);
  253. #endif
  254. }
  255. /**
  256. * @brief Send a mission_current message
  257. * @param chan MAVLink channel to send the message
  258. * @param struct The MAVLink struct to serialize
  259. */
  260. static inline void mavlink_msg_mission_current_send_struct(mavlink_channel_t chan, const mavlink_mission_current_t* mission_current)
  261. {
  262. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  263. 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);
  264. #else
  265. _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);
  266. #endif
  267. }
  268. #if MAVLINK_MSG_ID_MISSION_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  269. /*
  270. This variant of _send() can be used to save stack space by re-using
  271. memory from the receive buffer. The caller provides a
  272. mavlink_message_t which is the size of a full mavlink message. This
  273. is usually the receive buffer for the channel, and allows a reply to an
  274. incoming message with minimum stack space usage.
  275. */
  276. 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)
  277. {
  278. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  279. char *buf = (char *)msgbuf;
  280. _mav_put_uint16_t(buf, 0, seq);
  281. _mav_put_uint16_t(buf, 2, total);
  282. _mav_put_uint8_t(buf, 4, mission_state);
  283. _mav_put_uint8_t(buf, 5, mission_mode);
  284. _mav_put_uint32_t(buf, 6, mission_id);
  285. _mav_put_uint32_t(buf, 10, fence_id);
  286. _mav_put_uint32_t(buf, 14, rally_points_id);
  287. _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);
  288. #else
  289. mavlink_mission_current_t *packet = (mavlink_mission_current_t *)msgbuf;
  290. packet->seq = seq;
  291. packet->total = total;
  292. packet->mission_state = mission_state;
  293. packet->mission_mode = mission_mode;
  294. packet->mission_id = mission_id;
  295. packet->fence_id = fence_id;
  296. packet->rally_points_id = rally_points_id;
  297. _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);
  298. #endif
  299. }
  300. #endif
  301. #endif
  302. // MESSAGE MISSION_CURRENT UNPACKING
  303. /**
  304. * @brief Get field seq from mission_current message
  305. *
  306. * @return Sequence
  307. */
  308. static inline uint16_t mavlink_msg_mission_current_get_seq(const mavlink_message_t* msg)
  309. {
  310. return _MAV_RETURN_uint16_t(msg, 0);
  311. }
  312. /**
  313. * @brief Get field total from mission_current message
  314. *
  315. * @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.
  316. */
  317. static inline uint16_t mavlink_msg_mission_current_get_total(const mavlink_message_t* msg)
  318. {
  319. return _MAV_RETURN_uint16_t(msg, 2);
  320. }
  321. /**
  322. * @brief Get field mission_state from mission_current message
  323. *
  324. * @return Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.
  325. */
  326. static inline uint8_t mavlink_msg_mission_current_get_mission_state(const mavlink_message_t* msg)
  327. {
  328. return _MAV_RETURN_uint8_t(msg, 4);
  329. }
  330. /**
  331. * @brief Get field mission_mode from mission_current message
  332. *
  333. * @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).
  334. */
  335. static inline uint8_t mavlink_msg_mission_current_get_mission_mode(const mavlink_message_t* msg)
  336. {
  337. return _MAV_RETURN_uint8_t(msg, 5);
  338. }
  339. /**
  340. * @brief Get field mission_id from mission_current message
  341. *
  342. * @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).
  343. */
  344. static inline uint32_t mavlink_msg_mission_current_get_mission_id(const mavlink_message_t* msg)
  345. {
  346. return _MAV_RETURN_uint32_t(msg, 6);
  347. }
  348. /**
  349. * @brief Get field fence_id from mission_current message
  350. *
  351. * @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).
  352. */
  353. static inline uint32_t mavlink_msg_mission_current_get_fence_id(const mavlink_message_t* msg)
  354. {
  355. return _MAV_RETURN_uint32_t(msg, 10);
  356. }
  357. /**
  358. * @brief Get field rally_points_id from mission_current message
  359. *
  360. * @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).
  361. */
  362. static inline uint32_t mavlink_msg_mission_current_get_rally_points_id(const mavlink_message_t* msg)
  363. {
  364. return _MAV_RETURN_uint32_t(msg, 14);
  365. }
  366. /**
  367. * @brief Decode a mission_current message into a struct
  368. *
  369. * @param msg The message to decode
  370. * @param mission_current C-struct to decode the message contents into
  371. */
  372. static inline void mavlink_msg_mission_current_decode(const mavlink_message_t* msg, mavlink_mission_current_t* mission_current)
  373. {
  374. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  375. mission_current->seq = mavlink_msg_mission_current_get_seq(msg);
  376. mission_current->total = mavlink_msg_mission_current_get_total(msg);
  377. mission_current->mission_state = mavlink_msg_mission_current_get_mission_state(msg);
  378. mission_current->mission_mode = mavlink_msg_mission_current_get_mission_mode(msg);
  379. mission_current->mission_id = mavlink_msg_mission_current_get_mission_id(msg);
  380. mission_current->fence_id = mavlink_msg_mission_current_get_fence_id(msg);
  381. mission_current->rally_points_id = mavlink_msg_mission_current_get_rally_points_id(msg);
  382. #else
  383. uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_CURRENT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_CURRENT_LEN;
  384. memset(mission_current, 0, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
  385. memcpy(mission_current, _MAV_PAYLOAD(msg), len);
  386. #endif
  387. }