mavlink_msg_statustext.h 13 KB

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