Classes | Macros | Typedefs | Functions
mavlink_msg_radio_status.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_radio_status_t
 

Macros

#define MAVLINK_MESSAGE_INFO_RADIO_STATUS
 
#define MAVLINK_MSG_ID_109_CRC   185
 
#define MAVLINK_MSG_ID_109_LEN   9
 
#define MAVLINK_MSG_ID_RADIO_STATUS   109
 
#define MAVLINK_MSG_ID_RADIO_STATUS_CRC   185
 
#define MAVLINK_MSG_ID_RADIO_STATUS_LEN   9
 

Typedefs

typedef struct __mavlink_radio_status_t mavlink_radio_status_t
 

Functions

static void mavlink_msg_radio_status_decode (const mavlink_message_t *msg, mavlink_radio_status_t *radio_status)
 Decode a radio_status message into a struct. More...
 
static uint16_t mavlink_msg_radio_status_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_radio_status_t *radio_status)
 Encode a radio_status struct. More...
 
static uint16_t mavlink_msg_radio_status_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_radio_status_t *radio_status)
 Encode a radio_status struct on a channel. More...
 
static uint16_t mavlink_msg_radio_status_get_fixed (const mavlink_message_t *msg)
 Get field fixed from radio_status message. More...
 
static uint8_t mavlink_msg_radio_status_get_noise (const mavlink_message_t *msg)
 Get field noise from radio_status message. More...
 
static uint8_t mavlink_msg_radio_status_get_remnoise (const mavlink_message_t *msg)
 Get field remnoise from radio_status message. More...
 
static uint8_t mavlink_msg_radio_status_get_remrssi (const mavlink_message_t *msg)
 Get field remrssi from radio_status message. More...
 
static uint8_t mavlink_msg_radio_status_get_rssi (const mavlink_message_t *msg)
 Send a radio_status message. More...
 
static uint16_t mavlink_msg_radio_status_get_rxerrors (const mavlink_message_t *msg)
 Get field rxerrors from radio_status message. More...
 
static uint8_t mavlink_msg_radio_status_get_txbuf (const mavlink_message_t *msg)
 Get field txbuf from radio_status message. More...
 
static uint16_t mavlink_msg_radio_status_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
 Pack a radio_status message. More...
 
static uint16_t mavlink_msg_radio_status_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
 Pack a radio_status message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_RADIO_STATUS
Value:
{ \
"RADIO_STATUS", \
7, \
{ { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \
{ "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \
{ "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \
{ "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_status_t, remrssi) }, \
{ "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_status_t, txbuf) }, \
{ "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_status_t, noise) }, \
{ "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_status_t, remnoise) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 24 of file mavlink_msg_radio_status.h.

#define MAVLINK_MSG_ID_109_CRC   185

Definition at line 20 of file mavlink_msg_radio_status.h.

#define MAVLINK_MSG_ID_109_LEN   9

Definition at line 17 of file mavlink_msg_radio_status.h.

#define MAVLINK_MSG_ID_RADIO_STATUS   109

Definition at line 3 of file mavlink_msg_radio_status.h.

#define MAVLINK_MSG_ID_RADIO_STATUS_CRC   185

Definition at line 19 of file mavlink_msg_radio_status.h.

#define MAVLINK_MSG_ID_RADIO_STATUS_LEN   9

Definition at line 16 of file mavlink_msg_radio_status.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_radio_status_decode ( const mavlink_message_t *  msg,
mavlink_radio_status_t radio_status 
)
inlinestatic

Decode a radio_status message into a struct.

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

Definition at line 340 of file mavlink_msg_radio_status.h.

static uint16_t mavlink_msg_radio_status_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_radio_status_t radio_status 
)
inlinestatic

Encode a radio_status 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
radio_statusC-struct to read the message contents from

Definition at line 147 of file mavlink_msg_radio_status.h.

static uint16_t mavlink_msg_radio_status_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_radio_status_t radio_status 
)
inlinestatic

Encode a radio_status 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
radio_statusC-struct to read the message contents from

Definition at line 161 of file mavlink_msg_radio_status.h.

static uint16_t mavlink_msg_radio_status_get_fixed ( const mavlink_message_t *  msg)
inlinestatic

Get field fixed from radio_status message.

Returns
Count of error corrected packets

Definition at line 329 of file mavlink_msg_radio_status.h.

static uint8_t mavlink_msg_radio_status_get_noise ( const mavlink_message_t *  msg)
inlinestatic

Get field noise from radio_status message.

Returns
Background noise level

Definition at line 299 of file mavlink_msg_radio_status.h.

static uint8_t mavlink_msg_radio_status_get_remnoise ( const mavlink_message_t *  msg)
inlinestatic

Get field remnoise from radio_status message.

Returns
Remote background noise level

Definition at line 309 of file mavlink_msg_radio_status.h.

static uint8_t mavlink_msg_radio_status_get_remrssi ( const mavlink_message_t *  msg)
inlinestatic

Get field remrssi from radio_status message.

Returns
Remote signal strength

Definition at line 279 of file mavlink_msg_radio_status.h.

static uint8_t mavlink_msg_radio_status_get_rssi ( const mavlink_message_t *  msg)
inlinestatic

Send a radio_status message.

Parameters
chanMAVLink channel to send the message
rssiLocal signal strength
remrssiRemote signal strength
txbufRemaining free buffer space in percent.
noiseBackground noise level
remnoiseRemote background noise level
rxerrorsReceive errors
fixedCount of error corrected packets Get field rssi from radio_status message
Returns
Local signal strength

Definition at line 269 of file mavlink_msg_radio_status.h.

static uint16_t mavlink_msg_radio_status_get_rxerrors ( const mavlink_message_t *  msg)
inlinestatic

Get field rxerrors from radio_status message.

Returns
Receive errors

Definition at line 319 of file mavlink_msg_radio_status.h.

static uint8_t mavlink_msg_radio_status_get_txbuf ( const mavlink_message_t *  msg)
inlinestatic

Get field txbuf from radio_status message.

Returns
Remaining free buffer space in percent.

Definition at line 289 of file mavlink_msg_radio_status.h.

static uint16_t mavlink_msg_radio_status_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint8_t  rssi,
uint8_t  remrssi,
uint8_t  txbuf,
uint8_t  noise,
uint8_t  remnoise,
uint16_t  rxerrors,
uint16_t  fixed 
)
inlinestatic

Pack a radio_status 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
rssiLocal signal strength
remrssiRemote signal strength
txbufRemaining free buffer space in percent.
noiseBackground noise level
remnoiseRemote background noise level
rxerrorsReceive errors
fixedCount of error corrected packets
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 53 of file mavlink_msg_radio_status.h.

static uint16_t mavlink_msg_radio_status_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint8_t  rssi,
uint8_t  remrssi,
uint8_t  txbuf,
uint8_t  noise,
uint8_t  remnoise,
uint16_t  rxerrors,
uint16_t  fixed 
)
inlinestatic

Pack a radio_status 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
rssiLocal signal strength
remrssiRemote signal strength
txbufRemaining free buffer space in percent.
noiseBackground noise level
remnoiseRemote background noise level
rxerrorsReceive errors
fixedCount of error corrected packets
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 103 of file mavlink_msg_radio_status.h.



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