2
0

mavlink_msg_mission_request.h 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344
  1. #pragma once
  2. // MESSAGE MISSION_REQUEST PACKING
  3. #define MAVLINK_MSG_ID_MISSION_REQUEST 40
  4. typedef struct __mavlink_mission_request_t {
  5. uint16_t seq; /*< Sequence*/
  6. uint8_t target_system; /*< System ID*/
  7. uint8_t target_component; /*< Component ID*/
  8. uint8_t mission_type; /*< Mission type.*/
  9. } mavlink_mission_request_t;
  10. #define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 5
  11. #define MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN 4
  12. #define MAVLINK_MSG_ID_40_LEN 5
  13. #define MAVLINK_MSG_ID_40_MIN_LEN 4
  14. #define MAVLINK_MSG_ID_MISSION_REQUEST_CRC 230
  15. #define MAVLINK_MSG_ID_40_CRC 230
  16. #if MAVLINK_COMMAND_24BIT
  17. #define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \
  18. 40, \
  19. "MISSION_REQUEST", \
  20. 4, \
  21. { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \
  22. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \
  23. { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \
  24. { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_t, mission_type) }, \
  25. } \
  26. }
  27. #else
  28. #define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \
  29. "MISSION_REQUEST", \
  30. 4, \
  31. { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \
  32. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \
  33. { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \
  34. { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_t, mission_type) }, \
  35. } \
  36. }
  37. #endif
  38. /**
  39. * @brief Pack a mission_request message
  40. * @param system_id ID of this system
  41. * @param component_id ID of this component (e.g. 200 for IMU)
  42. * @param msg The MAVLink message to compress the data into
  43. *
  44. * @param target_system System ID
  45. * @param target_component Component ID
  46. * @param seq Sequence
  47. * @param mission_type Mission type.
  48. * @return length of the message in bytes (excluding serial stream start sign)
  49. */
  50. static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  51. uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type)
  52. {
  53. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  54. char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN];
  55. _mav_put_uint16_t(buf, 0, seq);
  56. _mav_put_uint8_t(buf, 2, target_system);
  57. _mav_put_uint8_t(buf, 3, target_component);
  58. _mav_put_uint8_t(buf, 4, mission_type);
  59. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
  60. #else
  61. mavlink_mission_request_t packet;
  62. packet.seq = seq;
  63. packet.target_system = target_system;
  64. packet.target_component = target_component;
  65. packet.mission_type = mission_type;
  66. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
  67. #endif
  68. msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST;
  69. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
  70. }
  71. /**
  72. * @brief Pack a mission_request message
  73. * @param system_id ID of this system
  74. * @param component_id ID of this component (e.g. 200 for IMU)
  75. * @param status MAVLink status structure
  76. * @param msg The MAVLink message to compress the data into
  77. *
  78. * @param target_system System ID
  79. * @param target_component Component ID
  80. * @param seq Sequence
  81. * @param mission_type Mission type.
  82. * @return length of the message in bytes (excluding serial stream start sign)
  83. */
  84. static inline uint16_t mavlink_msg_mission_request_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  85. uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type)
  86. {
  87. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  88. char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN];
  89. _mav_put_uint16_t(buf, 0, seq);
  90. _mav_put_uint8_t(buf, 2, target_system);
  91. _mav_put_uint8_t(buf, 3, target_component);
  92. _mav_put_uint8_t(buf, 4, mission_type);
  93. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
  94. #else
  95. mavlink_mission_request_t packet;
  96. packet.seq = seq;
  97. packet.target_system = target_system;
  98. packet.target_component = target_component;
  99. packet.mission_type = mission_type;
  100. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
  101. #endif
  102. msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST;
  103. #if MAVLINK_CRC_EXTRA
  104. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
  105. #else
  106. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
  107. #endif
  108. }
  109. /**
  110. * @brief Pack a mission_request message on a channel
  111. * @param system_id ID of this system
  112. * @param component_id ID of this component (e.g. 200 for IMU)
  113. * @param chan The MAVLink channel this message will be sent over
  114. * @param msg The MAVLink message to compress the data into
  115. * @param target_system System ID
  116. * @param target_component Component ID
  117. * @param seq Sequence
  118. * @param mission_type Mission type.
  119. * @return length of the message in bytes (excluding serial stream start sign)
  120. */
  121. static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  122. mavlink_message_t* msg,
  123. uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t mission_type)
  124. {
  125. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  126. char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN];
  127. _mav_put_uint16_t(buf, 0, seq);
  128. _mav_put_uint8_t(buf, 2, target_system);
  129. _mav_put_uint8_t(buf, 3, target_component);
  130. _mav_put_uint8_t(buf, 4, mission_type);
  131. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
  132. #else
  133. mavlink_mission_request_t packet;
  134. packet.seq = seq;
  135. packet.target_system = target_system;
  136. packet.target_component = target_component;
  137. packet.mission_type = mission_type;
  138. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
  139. #endif
  140. msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST;
  141. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
  142. }
  143. /**
  144. * @brief Encode a mission_request struct
  145. *
  146. * @param system_id ID of this system
  147. * @param component_id ID of this component (e.g. 200 for IMU)
  148. * @param msg The MAVLink message to compress the data into
  149. * @param mission_request C-struct to read the message contents from
  150. */
  151. static inline uint16_t mavlink_msg_mission_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request)
  152. {
  153. return mavlink_msg_mission_request_pack(system_id, component_id, msg, mission_request->target_system, mission_request->target_component, mission_request->seq, mission_request->mission_type);
  154. }
  155. /**
  156. * @brief Encode a mission_request struct on a channel
  157. *
  158. * @param system_id ID of this system
  159. * @param component_id ID of this component (e.g. 200 for IMU)
  160. * @param chan The MAVLink channel this message will be sent over
  161. * @param msg The MAVLink message to compress the data into
  162. * @param mission_request C-struct to read the message contents from
  163. */
  164. static inline uint16_t mavlink_msg_mission_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request)
  165. {
  166. return mavlink_msg_mission_request_pack_chan(system_id, component_id, chan, msg, mission_request->target_system, mission_request->target_component, mission_request->seq, mission_request->mission_type);
  167. }
  168. /**
  169. * @brief Encode a mission_request struct with provided status structure
  170. *
  171. * @param system_id ID of this system
  172. * @param component_id ID of this component (e.g. 200 for IMU)
  173. * @param status MAVLink status structure
  174. * @param msg The MAVLink message to compress the data into
  175. * @param mission_request C-struct to read the message contents from
  176. */
  177. static inline uint16_t mavlink_msg_mission_request_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request)
  178. {
  179. return mavlink_msg_mission_request_pack_status(system_id, component_id, _status, msg, mission_request->target_system, mission_request->target_component, mission_request->seq, mission_request->mission_type);
  180. }
  181. /**
  182. * @brief Send a mission_request message
  183. * @param chan MAVLink channel to send the message
  184. *
  185. * @param target_system System ID
  186. * @param target_component Component ID
  187. * @param seq Sequence
  188. * @param mission_type Mission type.
  189. */
  190. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  191. static inline void mavlink_msg_mission_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type)
  192. {
  193. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  194. char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN];
  195. _mav_put_uint16_t(buf, 0, seq);
  196. _mav_put_uint8_t(buf, 2, target_system);
  197. _mav_put_uint8_t(buf, 3, target_component);
  198. _mav_put_uint8_t(buf, 4, mission_type);
  199. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
  200. #else
  201. mavlink_mission_request_t packet;
  202. packet.seq = seq;
  203. packet.target_system = target_system;
  204. packet.target_component = target_component;
  205. packet.mission_type = mission_type;
  206. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
  207. #endif
  208. }
  209. /**
  210. * @brief Send a mission_request message
  211. * @param chan MAVLink channel to send the message
  212. * @param struct The MAVLink struct to serialize
  213. */
  214. static inline void mavlink_msg_mission_request_send_struct(mavlink_channel_t chan, const mavlink_mission_request_t* mission_request)
  215. {
  216. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  217. mavlink_msg_mission_request_send(chan, mission_request->target_system, mission_request->target_component, mission_request->seq, mission_request->mission_type);
  218. #else
  219. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)mission_request, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
  220. #endif
  221. }
  222. #if MAVLINK_MSG_ID_MISSION_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  223. /*
  224. This variant of _send() can be used to save stack space by re-using
  225. memory from the receive buffer. The caller provides a
  226. mavlink_message_t which is the size of a full mavlink message. This
  227. is usually the receive buffer for the channel, and allows a reply to an
  228. incoming message with minimum stack space usage.
  229. */
  230. static inline void mavlink_msg_mission_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type)
  231. {
  232. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  233. char *buf = (char *)msgbuf;
  234. _mav_put_uint16_t(buf, 0, seq);
  235. _mav_put_uint8_t(buf, 2, target_system);
  236. _mav_put_uint8_t(buf, 3, target_component);
  237. _mav_put_uint8_t(buf, 4, mission_type);
  238. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
  239. #else
  240. mavlink_mission_request_t *packet = (mavlink_mission_request_t *)msgbuf;
  241. packet->seq = seq;
  242. packet->target_system = target_system;
  243. packet->target_component = target_component;
  244. packet->mission_type = mission_type;
  245. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
  246. #endif
  247. }
  248. #endif
  249. #endif
  250. // MESSAGE MISSION_REQUEST UNPACKING
  251. /**
  252. * @brief Get field target_system from mission_request message
  253. *
  254. * @return System ID
  255. */
  256. static inline uint8_t mavlink_msg_mission_request_get_target_system(const mavlink_message_t* msg)
  257. {
  258. return _MAV_RETURN_uint8_t(msg, 2);
  259. }
  260. /**
  261. * @brief Get field target_component from mission_request message
  262. *
  263. * @return Component ID
  264. */
  265. static inline uint8_t mavlink_msg_mission_request_get_target_component(const mavlink_message_t* msg)
  266. {
  267. return _MAV_RETURN_uint8_t(msg, 3);
  268. }
  269. /**
  270. * @brief Get field seq from mission_request message
  271. *
  272. * @return Sequence
  273. */
  274. static inline uint16_t mavlink_msg_mission_request_get_seq(const mavlink_message_t* msg)
  275. {
  276. return _MAV_RETURN_uint16_t(msg, 0);
  277. }
  278. /**
  279. * @brief Get field mission_type from mission_request message
  280. *
  281. * @return Mission type.
  282. */
  283. static inline uint8_t mavlink_msg_mission_request_get_mission_type(const mavlink_message_t* msg)
  284. {
  285. return _MAV_RETURN_uint8_t(msg, 4);
  286. }
  287. /**
  288. * @brief Decode a mission_request message into a struct
  289. *
  290. * @param msg The message to decode
  291. * @param mission_request C-struct to decode the message contents into
  292. */
  293. static inline void mavlink_msg_mission_request_decode(const mavlink_message_t* msg, mavlink_mission_request_t* mission_request)
  294. {
  295. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  296. mission_request->seq = mavlink_msg_mission_request_get_seq(msg);
  297. mission_request->target_system = mavlink_msg_mission_request_get_target_system(msg);
  298. mission_request->target_component = mavlink_msg_mission_request_get_target_component(msg);
  299. mission_request->mission_type = mavlink_msg_mission_request_get_mission_type(msg);
  300. #else
  301. uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_LEN;
  302. memset(mission_request, 0, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
  303. memcpy(mission_request, _MAV_PAYLOAD(msg), len);
  304. #endif
  305. }