Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE STATUSTEXT PACKING
2
 
3
#define MAVLINK_MSG_ID_STATUSTEXT 253
4
 
5
typedef struct __mavlink_statustext_t
6
{
7
 uint8_t severity; ///< Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
8
 char text[50]; ///< Status text message, without null termination character
9
} mavlink_statustext_t;
10
 
11
#define MAVLINK_MSG_ID_STATUSTEXT_LEN 51
12
#define MAVLINK_MSG_ID_253_LEN 51
13
 
14
#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50
15
 
16
#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \
17
        "STATUSTEXT", \
18
        2, \
19
        {  { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \
20
         { "text", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_statustext_t, text) }, \
21
         } \
22
}
23
 
24
 
25
/**
26
 * @brief Pack a statustext message
27
 * @param system_id ID of this system
28
 * @param component_id ID of this component (e.g. 200 for IMU)
29
 * @param msg The MAVLink message to compress the data into
30
 *
31
 * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
32
 * @param text Status text message, without null termination character
33
 * @return length of the message in bytes (excluding serial stream start sign)
34
 */
35
static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
36
                                                       uint8_t severity, const char *text)
37
{
38
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
39
        char buf[51];
40
        _mav_put_uint8_t(buf, 0, severity);
41
        _mav_put_char_array(buf, 1, text, 50);
42
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 51);
43
#else
44
        mavlink_statustext_t packet;
45
        packet.severity = severity;
46
        mav_array_memcpy(packet.text, text, sizeof(char)*50);
47
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 51);
48
#endif
49
 
50
        msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
51
        return mavlink_finalize_message(msg, system_id, component_id, 51, 83);
52
}
53
 
54
/**
55
 * @brief Pack a statustext message on a channel
56
 * @param system_id ID of this system
57
 * @param component_id ID of this component (e.g. 200 for IMU)
58
 * @param chan The MAVLink channel this message was sent over
59
 * @param msg The MAVLink message to compress the data into
60
 * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
61
 * @param text Status text message, without null termination character
62
 * @return length of the message in bytes (excluding serial stream start sign)
63
 */
64
static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
65
                                                           mavlink_message_t* msg,
66
                                                           uint8_t severity,const char *text)
67
{
68
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
69
        char buf[51];
70
        _mav_put_uint8_t(buf, 0, severity);
71
        _mav_put_char_array(buf, 1, text, 50);
72
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 51);
73
#else
74
        mavlink_statustext_t packet;
75
        packet.severity = severity;
76
        mav_array_memcpy(packet.text, text, sizeof(char)*50);
77
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 51);
78
#endif
79
 
80
        msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
81
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 51, 83);
82
}
83
 
84
/**
85
 * @brief Encode a statustext struct into a message
86
 *
87
 * @param system_id ID of this system
88
 * @param component_id ID of this component (e.g. 200 for IMU)
89
 * @param msg The MAVLink message to compress the data into
90
 * @param statustext C-struct to read the message contents from
91
 */
92
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)
93
{
94
        return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text);
95
}
96
 
97
/**
98
 * @brief Send a statustext message
99
 * @param chan MAVLink channel to send the message
100
 *
101
 * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
102
 * @param text Status text message, without null termination character
103
 */
104
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
105
 
106
static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const char *text)
107
{
108
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
109
        char buf[51];
110
        _mav_put_uint8_t(buf, 0, severity);
111
        _mav_put_char_array(buf, 1, text, 50);
112
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, 51, 83);
113
#else
114
        mavlink_statustext_t packet;
115
        packet.severity = severity;
116
        mav_array_memcpy(packet.text, text, sizeof(char)*50);
117
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, 51, 83);
118
#endif
119
}
120
 
121
#endif
122
 
123
// MESSAGE STATUSTEXT UNPACKING
124
 
125
 
126
/**
127
 * @brief Get field severity from statustext message
128
 *
129
 * @return Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
130
 */
131
static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg)
132
{
133
        return _MAV_RETURN_uint8_t(msg,  0);
134
}
135
 
136
/**
137
 * @brief Get field text from statustext message
138
 *
139
 * @return Status text message, without null termination character
140
 */
141
static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, char *text)
142
{
143
        return _MAV_RETURN_char_array(msg, text, 50,  1);
144
}
145
 
146
/**
147
 * @brief Decode a statustext message into a struct
148
 *
149
 * @param msg The message to decode
150
 * @param statustext C-struct to decode the message contents into
151
 */
152
static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext)
153
{
154
#if MAVLINK_NEED_BYTE_SWAP
155
        statustext->severity = mavlink_msg_statustext_get_severity(msg);
156
        mavlink_msg_statustext_get_text(msg, statustext->text);
157
#else
158
        memcpy(statustext, _MAV_PAYLOAD(msg), 51);
159
#endif
160
}