aboutsummaryrefslogtreecommitdiff
path: root/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h
diff options
context:
space:
mode:
Diffstat (limited to 'mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h')
-rw-r--r--mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h100
1 files changed, 38 insertions, 62 deletions
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h
index 536ca0634..b10ae2b1d 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h
@@ -2,25 +2,29 @@
#define MAVLINK_MSG_ID_STATUSTEXT 253
-typedef struct __mavlink_statustext_t
-{
- uint8_t severity; ///< Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
- char text[50]; ///< Status text message, without null termination character
-} mavlink_statustext_t;
-
#define MAVLINK_MSG_ID_STATUSTEXT_LEN 51
-#define MAVLINK_MSG_ID_253_LEN 51
+#define MAVLINK_MSG_ID_253_LEN MAVLINK_MSG_ID_STATUSTEXT_LEN
#define MAVLINK_MSG_ID_STATUSTEXT_CRC 83
-#define MAVLINK_MSG_ID_253_CRC 83
+#define MAVLINK_MSG_ID_253_CRC MAVLINK_MSG_ID_STATUSTEXT_CRC
-#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50
+#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 49 ///< Length in bytes
+
+#define MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES 1
+
+typedef struct __mavlink_statustext_t
+{
+ uint8_t severity; ///< Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
+ char text[49]; ///< Status text message, without null termination character
+ uint8_t _field_len_text; ///< Length of status text message
+} mavlink_statustext_t;
#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \
"STATUSTEXT", \
- 2, \
+ 3, \
{ { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \
- { "text", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_statustext_t, text) }, \
+ { "text", NULL, MAVLINK_TYPE_CHAR, -1, -1, -1 }, \
+ { "_field_len_text", NULL, MAVLINK_TYPE_UINT8_T, 0, -1, 1 } \
} \
}
@@ -38,24 +42,16 @@ typedef struct __mavlink_statustext_t
static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t severity, const char *text)
{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ uint8_t _field_len_text;
char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN];
_mav_put_uint8_t(buf, 0, severity);
- _mav_put_char_array(buf, 1, text, 50);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#else
- mavlink_statustext_t packet;
- packet.severity = severity;
- mav_array_memcpy(packet.text, text, sizeof(char)*50);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#endif
+ _field_len_text = mav_string_copy(&buf[1], text, sizeof(char)*49);
+ _mav_put_uint8_t(buf, 1 + _field_len_text, _field_len_text);
+ uint16_t msglen = 1 + _field_len_text + MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, msglen);
msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
-#if MAVLINK_CRC_EXTRA
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC);
-#else
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#endif
+ return mavlink_finalize_message(msg, system_id, component_id, msglen, MAVLINK_MSG_ID_STATUSTEXT_CRC);
}
/**
@@ -72,24 +68,16 @@ static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8
mavlink_message_t* msg,
uint8_t severity,const char *text)
{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ uint8_t _field_len_text;
char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN];
_mav_put_uint8_t(buf, 0, severity);
- _mav_put_char_array(buf, 1, text, 50);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#else
- mavlink_statustext_t packet;
- packet.severity = severity;
- mav_array_memcpy(packet.text, text, sizeof(char)*50);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#endif
+ _field_len_text = mav_string_copy(&buf[1], text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
+ _mav_put_uint8_t(buf, 1 + _field_len_text, _field_len_text);
+ uint16_t msglen = 1 + _field_len_text + MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, msglen);
msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
-#if MAVLINK_CRC_EXTRA
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC);
-#else
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#endif
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, msglen, MAVLINK_MSG_ID_STATUSTEXT_CRC);
}
/**
@@ -130,25 +118,14 @@ static inline uint16_t mavlink_msg_statustext_encode_chan(uint8_t system_id, uin
static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const char *text)
{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ uint8_t _field_len_text;
char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN];
_mav_put_uint8_t(buf, 0, severity);
- _mav_put_char_array(buf, 1, text, 50);
-#if MAVLINK_CRC_EXTRA
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#endif
-#else
- mavlink_statustext_t packet;
- packet.severity = severity;
- mav_array_memcpy(packet.text, text, sizeof(char)*50);
-#if MAVLINK_CRC_EXTRA
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#endif
-#endif
+ _field_len_text = mav_string_copy(&buf[1], text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
+ _mav_put_uint8_t(buf, 1 + _field_len_text, _field_len_text);
+ uint16_t msglen = 1 + _field_len_text + MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, msglen);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, msglen, MAVLINK_MSG_ID_STATUSTEXT_CRC);
}
#endif
@@ -173,7 +150,8 @@ static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_
*/
static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, char *text)
{
- return _MAV_RETURN_char_array(msg, text, 50, 1);
+ uint8_t len = _MAV_RETURN_uint8_t(msg, msg->len - MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES + 0);
+ return _MAV_RETURN_char_array(msg, text, len, 1);
}
/**
@@ -184,10 +162,8 @@ static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t*
*/
static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext)
{
-#if MAVLINK_NEED_BYTE_SWAP
+ statustext->_field_len_text = _MAV_RETURN_uint8_t(msg, msg->len - MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES + 0);
statustext->severity = mavlink_msg_statustext_get_severity(msg);
- mavlink_msg_statustext_get_text(msg, statustext->text);
-#else
- memcpy(statustext, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#endif
+ /* copy the string, but at maximum to the full field length or the announced string length, depending on which is shorter */
+ strncpy(statustext->text, _MAV_PAYLOAD(msg+1), (statustext->_field_len_text < MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN) ? statustext->_field_len_text : MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
}