mavlink_msg_mission_count.h 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343
  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 on a channel
  91. * @param system_id ID of this system
  92. * @param component_id ID of this component (e.g. 200 for IMU)
  93. * @param chan The MAVLink channel this message will be sent over
  94. * @param msg The MAVLink message to compress the data into
  95. * @param target_system System ID
  96. * @param target_component Component ID
  97. * @param count Number of mission items in the sequence
  98. * @param mission_type Mission type.
  99. * @param opaque_id Id of current on-vehicle mission, fence, or rally point plan (on download from vehicle).
  100. This field is used when downloading a plan from a vehicle to a GCS.
  101. 0 on upload to the vehicle from GCS.
  102. 0 if plan ids are not supported.
  103. 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.
  104. 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).
  105. * @return length of the message in bytes (excluding serial stream start sign)
  106. */
  107. static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  108. 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. 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);
  130. }
  131. /**
  132. * @brief Encode a mission_count struct
  133. *
  134. * @param system_id ID of this system
  135. * @param component_id ID of this component (e.g. 200 for IMU)
  136. * @param msg The MAVLink message to compress the data into
  137. * @param mission_count C-struct to read the message contents from
  138. */
  139. 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)
  140. {
  141. 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);
  142. }
  143. /**
  144. * @brief Encode a mission_count struct on a channel
  145. *
  146. * @param system_id ID of this system
  147. * @param component_id ID of this component (e.g. 200 for IMU)
  148. * @param chan The MAVLink channel this message will be sent over
  149. * @param msg The MAVLink message to compress the data into
  150. * @param mission_count C-struct to read the message contents from
  151. */
  152. 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)
  153. {
  154. 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);
  155. }
  156. /**
  157. * @brief Send a mission_count message
  158. * @param chan MAVLink channel to send the message
  159. *
  160. * @param target_system System ID
  161. * @param target_component Component ID
  162. * @param count Number of mission items in the sequence
  163. * @param mission_type Mission type.
  164. * @param opaque_id Id of current on-vehicle mission, fence, or rally point plan (on download from vehicle).
  165. This field is used when downloading a plan from a vehicle to a GCS.
  166. 0 on upload to the vehicle from GCS.
  167. 0 if plan ids are not supported.
  168. 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.
  169. 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).
  170. */
  171. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  172. 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)
  173. {
  174. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  175. char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN];
  176. _mav_put_uint16_t(buf, 0, count);
  177. _mav_put_uint8_t(buf, 2, target_system);
  178. _mav_put_uint8_t(buf, 3, target_component);
  179. _mav_put_uint8_t(buf, 4, mission_type);
  180. _mav_put_uint32_t(buf, 5, opaque_id);
  181. _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);
  182. #else
  183. mavlink_mission_count_t packet;
  184. packet.count = count;
  185. packet.target_system = target_system;
  186. packet.target_component = target_component;
  187. packet.mission_type = mission_type;
  188. packet.opaque_id = opaque_id;
  189. _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);
  190. #endif
  191. }
  192. /**
  193. * @brief Send a mission_count message
  194. * @param chan MAVLink channel to send the message
  195. * @param struct The MAVLink struct to serialize
  196. */
  197. static inline void mavlink_msg_mission_count_send_struct(mavlink_channel_t chan, const mavlink_mission_count_t* mission_count)
  198. {
  199. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  200. 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);
  201. #else
  202. _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);
  203. #endif
  204. }
  205. #if MAVLINK_MSG_ID_MISSION_COUNT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  206. /*
  207. This variant of _send() can be used to save stack space by re-using
  208. memory from the receive buffer. The caller provides a
  209. mavlink_message_t which is the size of a full mavlink message. This
  210. is usually the receive buffer for the channel, and allows a reply to an
  211. incoming message with minimum stack space usage.
  212. */
  213. 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)
  214. {
  215. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  216. char *buf = (char *)msgbuf;
  217. _mav_put_uint16_t(buf, 0, count);
  218. _mav_put_uint8_t(buf, 2, target_system);
  219. _mav_put_uint8_t(buf, 3, target_component);
  220. _mav_put_uint8_t(buf, 4, mission_type);
  221. _mav_put_uint32_t(buf, 5, opaque_id);
  222. _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);
  223. #else
  224. mavlink_mission_count_t *packet = (mavlink_mission_count_t *)msgbuf;
  225. packet->count = count;
  226. packet->target_system = target_system;
  227. packet->target_component = target_component;
  228. packet->mission_type = mission_type;
  229. packet->opaque_id = opaque_id;
  230. _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);
  231. #endif
  232. }
  233. #endif
  234. #endif
  235. // MESSAGE MISSION_COUNT UNPACKING
  236. /**
  237. * @brief Get field target_system from mission_count message
  238. *
  239. * @return System ID
  240. */
  241. static inline uint8_t mavlink_msg_mission_count_get_target_system(const mavlink_message_t* msg)
  242. {
  243. return _MAV_RETURN_uint8_t(msg, 2);
  244. }
  245. /**
  246. * @brief Get field target_component from mission_count message
  247. *
  248. * @return Component ID
  249. */
  250. static inline uint8_t mavlink_msg_mission_count_get_target_component(const mavlink_message_t* msg)
  251. {
  252. return _MAV_RETURN_uint8_t(msg, 3);
  253. }
  254. /**
  255. * @brief Get field count from mission_count message
  256. *
  257. * @return Number of mission items in the sequence
  258. */
  259. static inline uint16_t mavlink_msg_mission_count_get_count(const mavlink_message_t* msg)
  260. {
  261. return _MAV_RETURN_uint16_t(msg, 0);
  262. }
  263. /**
  264. * @brief Get field mission_type from mission_count message
  265. *
  266. * @return Mission type.
  267. */
  268. static inline uint8_t mavlink_msg_mission_count_get_mission_type(const mavlink_message_t* msg)
  269. {
  270. return _MAV_RETURN_uint8_t(msg, 4);
  271. }
  272. /**
  273. * @brief Get field opaque_id from mission_count message
  274. *
  275. * @return Id of current on-vehicle mission, fence, or rally point plan (on download from vehicle).
  276. This field is used when downloading a plan from a vehicle to a GCS.
  277. 0 on upload to the vehicle from GCS.
  278. 0 if plan ids are not supported.
  279. 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.
  280. 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).
  281. */
  282. static inline uint32_t mavlink_msg_mission_count_get_opaque_id(const mavlink_message_t* msg)
  283. {
  284. return _MAV_RETURN_uint32_t(msg, 5);
  285. }
  286. /**
  287. * @brief Decode a mission_count message into a struct
  288. *
  289. * @param msg The message to decode
  290. * @param mission_count C-struct to decode the message contents into
  291. */
  292. static inline void mavlink_msg_mission_count_decode(const mavlink_message_t* msg, mavlink_mission_count_t* mission_count)
  293. {
  294. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  295. mission_count->count = mavlink_msg_mission_count_get_count(msg);
  296. mission_count->target_system = mavlink_msg_mission_count_get_target_system(msg);
  297. mission_count->target_component = mavlink_msg_mission_count_get_target_component(msg);
  298. mission_count->mission_type = mavlink_msg_mission_count_get_mission_type(msg);
  299. mission_count->opaque_id = mavlink_msg_mission_count_get_opaque_id(msg);
  300. #else
  301. uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_COUNT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_COUNT_LEN;
  302. memset(mission_count, 0, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
  303. memcpy(mission_count, _MAV_PAYLOAD(msg), len);
  304. #endif
  305. }