mavlink_msg_statustext.h 16 KB

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