pub struct RADIO_STATUS_DATA {
pub rxerrors: u16,
pub fixed: u16,
pub rssi: u8,
pub remrssi: u8,
pub txbuf: u8,
pub noise: u8,
pub remnoise: u8,
}matrixpilot only.Expand description
Status generated by radio and injected into MAVLink stream.
ID: 109
Fields§
§rxerrors: u16Count of radio packet receive errors (since boot).
fixed: u16Count of error corrected radio packets (since boot).
rssi: u8Local (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.
remrssi: u8Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.
txbuf: u8Remaining free transmitter buffer space.
noise: u8Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown.
remnoise: u8Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown.
Implementations§
Source§impl RADIO_STATUS_DATA
impl RADIO_STATUS_DATA
pub const ENCODED_LEN: usize = 9usize
pub const DEFAULT: Self
Trait Implementations§
Source§impl Clone for RADIO_STATUS_DATA
impl Clone for RADIO_STATUS_DATA
Source§fn clone(&self) -> RADIO_STATUS_DATA
fn clone(&self) -> RADIO_STATUS_DATA
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read more