
Go to the source code of this file.
Classes | |
| struct | __mavlink_radio_status_t |
Defines | |
| #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. | |
| 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. | |
| 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. | |
| static uint16_t | mavlink_msg_radio_status_get_fixed (const mavlink_message_t *msg) |
| Get field fixed from radio_status message. | |
| static uint8_t | mavlink_msg_radio_status_get_noise (const mavlink_message_t *msg) |
| Get field noise from radio_status message. | |
| static uint8_t | mavlink_msg_radio_status_get_remnoise (const mavlink_message_t *msg) |
| Get field remnoise from radio_status message. | |
| static uint8_t | mavlink_msg_radio_status_get_remrssi (const mavlink_message_t *msg) |
| Get field remrssi from radio_status message. | |
| static uint8_t | mavlink_msg_radio_status_get_rssi (const mavlink_message_t *msg) |
| Send a radio_status message. | |
| static uint16_t | mavlink_msg_radio_status_get_rxerrors (const mavlink_message_t *msg) |
| Get field rxerrors from radio_status message. | |
| static uint8_t | mavlink_msg_radio_status_get_txbuf (const mavlink_message_t *msg) |
| Get field txbuf from radio_status message. | |
| 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. | |
| 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. | |
{ \
"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) }, \
} \
}
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 struct __mavlink_radio_status_t mavlink_radio_status_t |
| static void mavlink_msg_radio_status_decode | ( | const mavlink_message_t * | msg, |
| mavlink_radio_status_t * | radio_status | ||
| ) | [inline, static] |
Decode a radio_status message into a struct.
| msg | The message to decode |
| radio_status | C-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 | ||
| ) | [inline, static] |
Encode a radio_status struct.
| system_id | ID of this system |
| component_id | ID of this component (e.g. 200 for IMU) |
| msg | The MAVLink message to compress the data into |
| radio_status | C-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 | ||
| ) | [inline, static] |
Encode a radio_status struct on a channel.
| system_id | ID of this system |
| component_id | ID of this component (e.g. 200 for IMU) |
| chan | The MAVLink channel this message will be sent over |
| msg | The MAVLink message to compress the data into |
| radio_status | C-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 | ) | [inline, static] |
Get field fixed from radio_status message.
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 | ) | [inline, static] |
Get field noise from radio_status message.
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 | ) | [inline, static] |
Get field remnoise from radio_status message.
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 | ) | [inline, static] |
Get field remrssi from radio_status message.
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 | ) | [inline, static] |
Send a radio_status message.
| chan | MAVLink channel to send the message |
| rssi | Local signal strength |
| remrssi | Remote signal strength |
| txbuf | Remaining free buffer space in percent. |
| noise | Background noise level |
| remnoise | Remote background noise level |
| rxerrors | Receive errors |
| fixed | Count of error corrected packets Get field rssi from radio_status message |
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 | ) | [inline, static] |
Get field rxerrors from radio_status message.
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 | ) | [inline, static] |
Get field txbuf from radio_status message.
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 | ||
| ) | [inline, static] |
Pack a radio_status message.
| system_id | ID of this system |
| component_id | ID of this component (e.g. 200 for IMU) |
| msg | The MAVLink message to compress the data into |
| rssi | Local signal strength |
| remrssi | Remote signal strength |
| txbuf | Remaining free buffer space in percent. |
| noise | Background noise level |
| remnoise | Remote background noise level |
| rxerrors | Receive errors |
| fixed | Count of error corrected packets |
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 | ||
| ) | [inline, static] |
Pack a radio_status message on a channel.
| system_id | ID of this system |
| component_id | ID of this component (e.g. 200 for IMU) |
| chan | The MAVLink channel this message will be sent over |
| msg | The MAVLink message to compress the data into |
| rssi | Local signal strength |
| remrssi | Remote signal strength |
| txbuf | Remaining free buffer space in percent. |
| noise | Background noise level |
| remnoise | Remote background noise level |
| rxerrors | Receive errors |
| fixed | Count of error corrected packets |
Definition at line 103 of file mavlink_msg_radio_status.h.