mavlink_msg_fence_status.h 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372
  1. #pragma once
  2. // MESSAGE FENCE_STATUS PACKING
  3. #define MAVLINK_MSG_ID_FENCE_STATUS 162
  4. typedef struct __mavlink_fence_status_t {
  5. uint32_t breach_time; /*< [ms] Time (since boot) of last breach.*/
  6. uint16_t breach_count; /*< Number of fence breaches.*/
  7. uint8_t breach_status; /*< Breach status (0 if currently inside fence, 1 if outside).*/
  8. uint8_t breach_type; /*< Last breach type.*/
  9. uint8_t breach_mitigation; /*< Active action to prevent fence breach*/
  10. } mavlink_fence_status_t;
  11. #define MAVLINK_MSG_ID_FENCE_STATUS_LEN 9
  12. #define MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN 8
  13. #define MAVLINK_MSG_ID_162_LEN 9
  14. #define MAVLINK_MSG_ID_162_MIN_LEN 8
  15. #define MAVLINK_MSG_ID_FENCE_STATUS_CRC 189
  16. #define MAVLINK_MSG_ID_162_CRC 189
  17. #if MAVLINK_COMMAND_24BIT
  18. #define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \
  19. 162, \
  20. "FENCE_STATUS", \
  21. 5, \
  22. { { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_fence_status_t, breach_status) }, \
  23. { "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_fence_status_t, breach_count) }, \
  24. { "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_fence_status_t, breach_type) }, \
  25. { "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fence_status_t, breach_time) }, \
  26. { "breach_mitigation", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_status_t, breach_mitigation) }, \
  27. } \
  28. }
  29. #else
  30. #define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \
  31. "FENCE_STATUS", \
  32. 5, \
  33. { { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_fence_status_t, breach_status) }, \
  34. { "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_fence_status_t, breach_count) }, \
  35. { "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_fence_status_t, breach_type) }, \
  36. { "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fence_status_t, breach_time) }, \
  37. { "breach_mitigation", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_status_t, breach_mitigation) }, \
  38. } \
  39. }
  40. #endif
  41. /**
  42. * @brief Pack a fence_status message
  43. * @param system_id ID of this system
  44. * @param component_id ID of this component (e.g. 200 for IMU)
  45. * @param msg The MAVLink message to compress the data into
  46. *
  47. * @param breach_status Breach status (0 if currently inside fence, 1 if outside).
  48. * @param breach_count Number of fence breaches.
  49. * @param breach_type Last breach type.
  50. * @param breach_time [ms] Time (since boot) of last breach.
  51. * @param breach_mitigation Active action to prevent fence breach
  52. * @return length of the message in bytes (excluding serial stream start sign)
  53. */
  54. static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  55. uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time, uint8_t breach_mitigation)
  56. {
  57. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  58. char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN];
  59. _mav_put_uint32_t(buf, 0, breach_time);
  60. _mav_put_uint16_t(buf, 4, breach_count);
  61. _mav_put_uint8_t(buf, 6, breach_status);
  62. _mav_put_uint8_t(buf, 7, breach_type);
  63. _mav_put_uint8_t(buf, 8, breach_mitigation);
  64. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
  65. #else
  66. mavlink_fence_status_t packet;
  67. packet.breach_time = breach_time;
  68. packet.breach_count = breach_count;
  69. packet.breach_status = breach_status;
  70. packet.breach_type = breach_type;
  71. packet.breach_mitigation = breach_mitigation;
  72. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
  73. #endif
  74. msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS;
  75. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
  76. }
  77. /**
  78. * @brief Pack a fence_status message
  79. * @param system_id ID of this system
  80. * @param component_id ID of this component (e.g. 200 for IMU)
  81. * @param status MAVLink status structure
  82. * @param msg The MAVLink message to compress the data into
  83. *
  84. * @param breach_status Breach status (0 if currently inside fence, 1 if outside).
  85. * @param breach_count Number of fence breaches.
  86. * @param breach_type Last breach type.
  87. * @param breach_time [ms] Time (since boot) of last breach.
  88. * @param breach_mitigation Active action to prevent fence breach
  89. * @return length of the message in bytes (excluding serial stream start sign)
  90. */
  91. static inline uint16_t mavlink_msg_fence_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  92. uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time, uint8_t breach_mitigation)
  93. {
  94. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  95. char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN];
  96. _mav_put_uint32_t(buf, 0, breach_time);
  97. _mav_put_uint16_t(buf, 4, breach_count);
  98. _mav_put_uint8_t(buf, 6, breach_status);
  99. _mav_put_uint8_t(buf, 7, breach_type);
  100. _mav_put_uint8_t(buf, 8, breach_mitigation);
  101. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
  102. #else
  103. mavlink_fence_status_t packet;
  104. packet.breach_time = breach_time;
  105. packet.breach_count = breach_count;
  106. packet.breach_status = breach_status;
  107. packet.breach_type = breach_type;
  108. packet.breach_mitigation = breach_mitigation;
  109. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
  110. #endif
  111. msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS;
  112. #if MAVLINK_CRC_EXTRA
  113. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
  114. #else
  115. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
  116. #endif
  117. }
  118. /**
  119. * @brief Pack a fence_status message on a channel
  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 breach_status Breach status (0 if currently inside fence, 1 if outside).
  125. * @param breach_count Number of fence breaches.
  126. * @param breach_type Last breach type.
  127. * @param breach_time [ms] Time (since boot) of last breach.
  128. * @param breach_mitigation Active action to prevent fence breach
  129. * @return length of the message in bytes (excluding serial stream start sign)
  130. */
  131. static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  132. mavlink_message_t* msg,
  133. uint8_t breach_status,uint16_t breach_count,uint8_t breach_type,uint32_t breach_time,uint8_t breach_mitigation)
  134. {
  135. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  136. char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN];
  137. _mav_put_uint32_t(buf, 0, breach_time);
  138. _mav_put_uint16_t(buf, 4, breach_count);
  139. _mav_put_uint8_t(buf, 6, breach_status);
  140. _mav_put_uint8_t(buf, 7, breach_type);
  141. _mav_put_uint8_t(buf, 8, breach_mitigation);
  142. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
  143. #else
  144. mavlink_fence_status_t packet;
  145. packet.breach_time = breach_time;
  146. packet.breach_count = breach_count;
  147. packet.breach_status = breach_status;
  148. packet.breach_type = breach_type;
  149. packet.breach_mitigation = breach_mitigation;
  150. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
  151. #endif
  152. msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS;
  153. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
  154. }
  155. /**
  156. * @brief Encode a fence_status struct
  157. *
  158. * @param system_id ID of this system
  159. * @param component_id ID of this component (e.g. 200 for IMU)
  160. * @param msg The MAVLink message to compress the data into
  161. * @param fence_status C-struct to read the message contents from
  162. */
  163. static inline uint16_t mavlink_msg_fence_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status)
  164. {
  165. return mavlink_msg_fence_status_pack(system_id, component_id, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time, fence_status->breach_mitigation);
  166. }
  167. /**
  168. * @brief Encode a fence_status struct on a channel
  169. *
  170. * @param system_id ID of this system
  171. * @param component_id ID of this component (e.g. 200 for IMU)
  172. * @param chan The MAVLink channel this message will be sent over
  173. * @param msg The MAVLink message to compress the data into
  174. * @param fence_status C-struct to read the message contents from
  175. */
  176. static inline uint16_t mavlink_msg_fence_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status)
  177. {
  178. return mavlink_msg_fence_status_pack_chan(system_id, component_id, chan, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time, fence_status->breach_mitigation);
  179. }
  180. /**
  181. * @brief Encode a fence_status struct with provided status structure
  182. *
  183. * @param system_id ID of this system
  184. * @param component_id ID of this component (e.g. 200 for IMU)
  185. * @param status MAVLink status structure
  186. * @param msg The MAVLink message to compress the data into
  187. * @param fence_status C-struct to read the message contents from
  188. */
  189. static inline uint16_t mavlink_msg_fence_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status)
  190. {
  191. return mavlink_msg_fence_status_pack_status(system_id, component_id, _status, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time, fence_status->breach_mitigation);
  192. }
  193. /**
  194. * @brief Send a fence_status message
  195. * @param chan MAVLink channel to send the message
  196. *
  197. * @param breach_status Breach status (0 if currently inside fence, 1 if outside).
  198. * @param breach_count Number of fence breaches.
  199. * @param breach_type Last breach type.
  200. * @param breach_time [ms] Time (since boot) of last breach.
  201. * @param breach_mitigation Active action to prevent fence breach
  202. */
  203. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  204. static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time, uint8_t breach_mitigation)
  205. {
  206. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  207. char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN];
  208. _mav_put_uint32_t(buf, 0, breach_time);
  209. _mav_put_uint16_t(buf, 4, breach_count);
  210. _mav_put_uint8_t(buf, 6, breach_status);
  211. _mav_put_uint8_t(buf, 7, breach_type);
  212. _mav_put_uint8_t(buf, 8, breach_mitigation);
  213. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
  214. #else
  215. mavlink_fence_status_t packet;
  216. packet.breach_time = breach_time;
  217. packet.breach_count = breach_count;
  218. packet.breach_status = breach_status;
  219. packet.breach_type = breach_type;
  220. packet.breach_mitigation = breach_mitigation;
  221. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
  222. #endif
  223. }
  224. /**
  225. * @brief Send a fence_status message
  226. * @param chan MAVLink channel to send the message
  227. * @param struct The MAVLink struct to serialize
  228. */
  229. static inline void mavlink_msg_fence_status_send_struct(mavlink_channel_t chan, const mavlink_fence_status_t* fence_status)
  230. {
  231. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  232. mavlink_msg_fence_status_send(chan, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time, fence_status->breach_mitigation);
  233. #else
  234. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)fence_status, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
  235. #endif
  236. }
  237. #if MAVLINK_MSG_ID_FENCE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  238. /*
  239. This variant of _send() can be used to save stack space by re-using
  240. memory from the receive buffer. The caller provides a
  241. mavlink_message_t which is the size of a full mavlink message. This
  242. is usually the receive buffer for the channel, and allows a reply to an
  243. incoming message with minimum stack space usage.
  244. */
  245. static inline void mavlink_msg_fence_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time, uint8_t breach_mitigation)
  246. {
  247. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  248. char *buf = (char *)msgbuf;
  249. _mav_put_uint32_t(buf, 0, breach_time);
  250. _mav_put_uint16_t(buf, 4, breach_count);
  251. _mav_put_uint8_t(buf, 6, breach_status);
  252. _mav_put_uint8_t(buf, 7, breach_type);
  253. _mav_put_uint8_t(buf, 8, breach_mitigation);
  254. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
  255. #else
  256. mavlink_fence_status_t *packet = (mavlink_fence_status_t *)msgbuf;
  257. packet->breach_time = breach_time;
  258. packet->breach_count = breach_count;
  259. packet->breach_status = breach_status;
  260. packet->breach_type = breach_type;
  261. packet->breach_mitigation = breach_mitigation;
  262. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)packet, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
  263. #endif
  264. }
  265. #endif
  266. #endif
  267. // MESSAGE FENCE_STATUS UNPACKING
  268. /**
  269. * @brief Get field breach_status from fence_status message
  270. *
  271. * @return Breach status (0 if currently inside fence, 1 if outside).
  272. */
  273. static inline uint8_t mavlink_msg_fence_status_get_breach_status(const mavlink_message_t* msg)
  274. {
  275. return _MAV_RETURN_uint8_t(msg, 6);
  276. }
  277. /**
  278. * @brief Get field breach_count from fence_status message
  279. *
  280. * @return Number of fence breaches.
  281. */
  282. static inline uint16_t mavlink_msg_fence_status_get_breach_count(const mavlink_message_t* msg)
  283. {
  284. return _MAV_RETURN_uint16_t(msg, 4);
  285. }
  286. /**
  287. * @brief Get field breach_type from fence_status message
  288. *
  289. * @return Last breach type.
  290. */
  291. static inline uint8_t mavlink_msg_fence_status_get_breach_type(const mavlink_message_t* msg)
  292. {
  293. return _MAV_RETURN_uint8_t(msg, 7);
  294. }
  295. /**
  296. * @brief Get field breach_time from fence_status message
  297. *
  298. * @return [ms] Time (since boot) of last breach.
  299. */
  300. static inline uint32_t mavlink_msg_fence_status_get_breach_time(const mavlink_message_t* msg)
  301. {
  302. return _MAV_RETURN_uint32_t(msg, 0);
  303. }
  304. /**
  305. * @brief Get field breach_mitigation from fence_status message
  306. *
  307. * @return Active action to prevent fence breach
  308. */
  309. static inline uint8_t mavlink_msg_fence_status_get_breach_mitigation(const mavlink_message_t* msg)
  310. {
  311. return _MAV_RETURN_uint8_t(msg, 8);
  312. }
  313. /**
  314. * @brief Decode a fence_status message into a struct
  315. *
  316. * @param msg The message to decode
  317. * @param fence_status C-struct to decode the message contents into
  318. */
  319. static inline void mavlink_msg_fence_status_decode(const mavlink_message_t* msg, mavlink_fence_status_t* fence_status)
  320. {
  321. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  322. fence_status->breach_time = mavlink_msg_fence_status_get_breach_time(msg);
  323. fence_status->breach_count = mavlink_msg_fence_status_get_breach_count(msg);
  324. fence_status->breach_status = mavlink_msg_fence_status_get_breach_status(msg);
  325. fence_status->breach_type = mavlink_msg_fence_status_get_breach_type(msg);
  326. fence_status->breach_mitigation = mavlink_msg_fence_status_get_breach_mitigation(msg);
  327. #else
  328. uint8_t len = msg->len < MAVLINK_MSG_ID_FENCE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_FENCE_STATUS_LEN;
  329. memset(fence_status, 0, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
  330. memcpy(fence_status, _MAV_PAYLOAD(msg), len);
  331. #endif
  332. }