mavlink_msg_mission_request.h 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288
  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 on a channel
  73. * @param system_id ID of this system
  74. * @param component_id ID of this component (e.g. 200 for IMU)
  75. * @param chan The MAVLink channel this message will be sent over
  76. * @param msg The MAVLink message to compress the data into
  77. * @param target_system System ID
  78. * @param target_component Component ID
  79. * @param seq Sequence
  80. * @param mission_type Mission type.
  81. * @return length of the message in bytes (excluding serial stream start sign)
  82. */
  83. static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  84. 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. 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);
  104. }
  105. /**
  106. * @brief Encode a mission_request struct
  107. *
  108. * @param system_id ID of this system
  109. * @param component_id ID of this component (e.g. 200 for IMU)
  110. * @param msg The MAVLink message to compress the data into
  111. * @param mission_request C-struct to read the message contents from
  112. */
  113. 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)
  114. {
  115. 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);
  116. }
  117. /**
  118. * @brief Encode a mission_request struct on a channel
  119. *
  120. * @param system_id ID of this system
  121. * @param component_id ID of this component (e.g. 200 for IMU)
  122. * @param chan The MAVLink channel this message will be sent over
  123. * @param msg The MAVLink message to compress the data into
  124. * @param mission_request C-struct to read the message contents from
  125. */
  126. 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)
  127. {
  128. 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);
  129. }
  130. /**
  131. * @brief Send a mission_request message
  132. * @param chan MAVLink channel to send the message
  133. *
  134. * @param target_system System ID
  135. * @param target_component Component ID
  136. * @param seq Sequence
  137. * @param mission_type Mission type.
  138. */
  139. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  140. 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)
  141. {
  142. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  143. char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN];
  144. _mav_put_uint16_t(buf, 0, seq);
  145. _mav_put_uint8_t(buf, 2, target_system);
  146. _mav_put_uint8_t(buf, 3, target_component);
  147. _mav_put_uint8_t(buf, 4, mission_type);
  148. _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);
  149. #else
  150. mavlink_mission_request_t packet;
  151. packet.seq = seq;
  152. packet.target_system = target_system;
  153. packet.target_component = target_component;
  154. packet.mission_type = mission_type;
  155. _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);
  156. #endif
  157. }
  158. /**
  159. * @brief Send a mission_request message
  160. * @param chan MAVLink channel to send the message
  161. * @param struct The MAVLink struct to serialize
  162. */
  163. static inline void mavlink_msg_mission_request_send_struct(mavlink_channel_t chan, const mavlink_mission_request_t* mission_request)
  164. {
  165. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  166. mavlink_msg_mission_request_send(chan, mission_request->target_system, mission_request->target_component, mission_request->seq, mission_request->mission_type);
  167. #else
  168. _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);
  169. #endif
  170. }
  171. #if MAVLINK_MSG_ID_MISSION_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  172. /*
  173. This variant of _send() can be used to save stack space by re-using
  174. memory from the receive buffer. The caller provides a
  175. mavlink_message_t which is the size of a full mavlink message. This
  176. is usually the receive buffer for the channel, and allows a reply to an
  177. incoming message with minimum stack space usage.
  178. */
  179. 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)
  180. {
  181. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  182. char *buf = (char *)msgbuf;
  183. _mav_put_uint16_t(buf, 0, seq);
  184. _mav_put_uint8_t(buf, 2, target_system);
  185. _mav_put_uint8_t(buf, 3, target_component);
  186. _mav_put_uint8_t(buf, 4, mission_type);
  187. _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);
  188. #else
  189. mavlink_mission_request_t *packet = (mavlink_mission_request_t *)msgbuf;
  190. packet->seq = seq;
  191. packet->target_system = target_system;
  192. packet->target_component = target_component;
  193. packet->mission_type = mission_type;
  194. _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);
  195. #endif
  196. }
  197. #endif
  198. #endif
  199. // MESSAGE MISSION_REQUEST UNPACKING
  200. /**
  201. * @brief Get field target_system from mission_request message
  202. *
  203. * @return System ID
  204. */
  205. static inline uint8_t mavlink_msg_mission_request_get_target_system(const mavlink_message_t* msg)
  206. {
  207. return _MAV_RETURN_uint8_t(msg, 2);
  208. }
  209. /**
  210. * @brief Get field target_component from mission_request message
  211. *
  212. * @return Component ID
  213. */
  214. static inline uint8_t mavlink_msg_mission_request_get_target_component(const mavlink_message_t* msg)
  215. {
  216. return _MAV_RETURN_uint8_t(msg, 3);
  217. }
  218. /**
  219. * @brief Get field seq from mission_request message
  220. *
  221. * @return Sequence
  222. */
  223. static inline uint16_t mavlink_msg_mission_request_get_seq(const mavlink_message_t* msg)
  224. {
  225. return _MAV_RETURN_uint16_t(msg, 0);
  226. }
  227. /**
  228. * @brief Get field mission_type from mission_request message
  229. *
  230. * @return Mission type.
  231. */
  232. static inline uint8_t mavlink_msg_mission_request_get_mission_type(const mavlink_message_t* msg)
  233. {
  234. return _MAV_RETURN_uint8_t(msg, 4);
  235. }
  236. /**
  237. * @brief Decode a mission_request message into a struct
  238. *
  239. * @param msg The message to decode
  240. * @param mission_request C-struct to decode the message contents into
  241. */
  242. static inline void mavlink_msg_mission_request_decode(const mavlink_message_t* msg, mavlink_mission_request_t* mission_request)
  243. {
  244. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  245. mission_request->seq = mavlink_msg_mission_request_get_seq(msg);
  246. mission_request->target_system = mavlink_msg_mission_request_get_target_system(msg);
  247. mission_request->target_component = mavlink_msg_mission_request_get_target_component(msg);
  248. mission_request->mission_type = mavlink_msg_mission_request_get_mission_type(msg);
  249. #else
  250. uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_LEN;
  251. memset(mission_request, 0, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
  252. memcpy(mission_request, _MAV_PAYLOAD(msg), len);
  253. #endif
  254. }