Classes | Macros | Typedefs | Functions
mavlink_msg_statustext.h File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  __mavlink_statustext_t
 

Macros

#define MAVLINK_MESSAGE_INFO_STATUSTEXT
 
#define MAVLINK_MSG_ID_253_CRC   83
 
#define MAVLINK_MSG_ID_253_LEN   51
 
#define MAVLINK_MSG_ID_STATUSTEXT   253
 
#define MAVLINK_MSG_ID_STATUSTEXT_CRC   83
 
#define MAVLINK_MSG_ID_STATUSTEXT_LEN   51
 
#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN   50
 

Typedefs

typedef struct __mavlink_statustext_t mavlink_statustext_t
 

Functions

static void mavlink_msg_statustext_decode (const mavlink_message_t *msg, mavlink_statustext_t *statustext)
 Decode a statustext message into a struct. More...
 
static uint16_t mavlink_msg_statustext_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_statustext_t *statustext)
 Encode a statustext struct. More...
 
static 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)
 Encode a statustext struct on a channel. More...
 
static uint8_t mavlink_msg_statustext_get_severity (const mavlink_message_t *msg)
 Send a statustext message. More...
 
static uint16_t mavlink_msg_statustext_get_text (const mavlink_message_t *msg, char *text)
 Get field text from statustext message. More...
 
static uint16_t mavlink_msg_statustext_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t severity, const char *text)
 Pack a statustext message. More...
 
static uint16_t mavlink_msg_statustext_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t severity, const char *text)
 Pack a statustext message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_STATUSTEXT
Value:
{ \
"STATUSTEXT", \
2, \
{ { "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) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 19 of file mavlink_msg_statustext.h.

#define MAVLINK_MSG_ID_253_CRC   83

Definition at line 15 of file mavlink_msg_statustext.h.

#define MAVLINK_MSG_ID_253_LEN   51

Definition at line 12 of file mavlink_msg_statustext.h.

#define MAVLINK_MSG_ID_STATUSTEXT   253

Definition at line 3 of file mavlink_msg_statustext.h.

#define MAVLINK_MSG_ID_STATUSTEXT_CRC   83

Definition at line 14 of file mavlink_msg_statustext.h.

#define MAVLINK_MSG_ID_STATUSTEXT_LEN   51

Definition at line 11 of file mavlink_msg_statustext.h.

#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN   50

Definition at line 17 of file mavlink_msg_statustext.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_statustext_decode ( const mavlink_message_t *  msg,
mavlink_statustext_t statustext 
)
inlinestatic

Decode a statustext message into a struct.

Parameters
msgThe message to decode
statustextC-struct to decode the message contents into

Definition at line 217 of file mavlink_msg_statustext.h.

static uint16_t mavlink_msg_statustext_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_statustext_t statustext 
)
inlinestatic

Encode a statustext struct.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
statustextC-struct to read the message contents from

Definition at line 103 of file mavlink_msg_statustext.h.

static 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 
)
inlinestatic

Encode a statustext struct on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
statustextC-struct to read the message contents from

Definition at line 117 of file mavlink_msg_statustext.h.

static uint8_t mavlink_msg_statustext_get_severity ( const mavlink_message_t *  msg)
inlinestatic

Send a statustext message.

Parameters
chanMAVLink channel to send the message
severitySeverity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
textStatus text message, without null termination character Get field severity from statustext message
Returns
Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.

Definition at line 196 of file mavlink_msg_statustext.h.

static uint16_t mavlink_msg_statustext_get_text ( const mavlink_message_t *  msg,
char *  text 
)
inlinestatic

Get field text from statustext message.

Returns
Status text message, without null termination character

Definition at line 206 of file mavlink_msg_statustext.h.

static uint16_t mavlink_msg_statustext_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint8_t  severity,
const char *  text 
)
inlinestatic

Pack a statustext message.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
severitySeverity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
textStatus text message, without null termination character
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 38 of file mavlink_msg_statustext.h.

static uint16_t mavlink_msg_statustext_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint8_t  severity,
const char *  text 
)
inlinestatic

Pack a statustext message on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
severitySeverity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
textStatus text message, without null termination character
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 71 of file mavlink_msg_statustext.h.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:52