From caff5d0da2209dcfe25c10b97b1e4d6ea4acfae2 Mon Sep 17 00:00:00 2001 From: olliw42 Date: Thu, 15 Aug 2024 15:10:45 +0200 Subject: [PATCH] development.xml: RADIO_LINK_STATS message (revised) --- message_definitions/v1.0/development.xml | 60 ++++++++++++++++++++++++ 1 file changed, 60 insertions(+) diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index 37e1fd242d..2a03ef4650 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -23,6 +23,38 @@ Channel data may be out of date. This is set when the receiver is unable to validate incoming data from the transmitter and has therefore resent the last valid data it received. + + RADIO_LINK_STATS flags (bitmask). + + Rssi values are in negative dBm. Values 1..254 corresponds to -1..-254 dBm. 0: no reception, UINT8_MAX: unknown. + + + + RADIO_LINK_STATS antenna flags (bitmask). + The RX_RECEIVE and TX_RECEIVE flags indicate from which antenna the received data are taken for processing. + The RX_TRANSMIT and TX_TRANSMIT flags specify which antenna are transmitting data. + Both antenna 1 and antenna 2 transmit flags can be set simultaneously, e.g., in case of dual-band or dual-frequency systems. + If neither flag is set then antenna 1 should be assumed. + + + Rx receive antenna. If the flag is set, then the data received on antenna 2 are taken, else the data stems from antenna 1. + + + Rx transmit antenna. Data are transmitted on antenna 1. + + + Rx transmit antenna. Data are transmitted on antenna 2. + + + Tx receive antenna. If the flag is set, then the data received on antenna 2 are taken, else the data stems from antenna 1. + + + Tx transmit antenna. Data are transmitted on antenna 1. + + + Tx transmit antenna. Data are transmitted on antenna 2. + + @@ -96,5 +128,33 @@ Channel values are in centered 13 bit format. Range is -4096 to 4096, center is 0. Conversion to PWM is x * 5/32 + 1500. Channels with indexes equal or above count should be set to 0, to benefit from MAVLink's trailing-zero trimming. + + Radio link statistics for a MAVLink RC receiver or transmitter. Tx: ground-side device, Rx: vehicle-side device. + The message is normally emitted in regular time intervals upon each actual or expected receiption of an over-the-air data packet on the link. + A MAVLink RC receiver should emit it shortly after it emits a RADIO_RC_CHANNELS message (if it is emitting that message). + Per default, rssi values are in MAVLink units: 0 represents weakest signal, 254 represents maximum signal. + The RADIO_LINK_STATS_FLAGS_RSSI_DBM flag is set if the rssi units are negative dBm: 1..254 correspond to -1..-254 dBm, 0 represents no receiption. + The target_system field should normally be set to the system id of the system the link is connected to, typically the flight controller. + The target_component field can normally be set to 0, so that all components of the system can receive the message. + + System ID (ID of target system, normally flight controller). + Component ID (normally 0 for broadcast). + Radio link statistics flags. + Link quality of RC data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown. + Link quality of serial MAVLink data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown. + Rssi of antenna 1. 0: no reception, UINT8_MAX: unknown. + Noise on antenna 1. Radio link dependent. INT8_MAX: unknown. + Rssi of antenna 2. 0: no reception, UINT8_MAX: use rx_rssi1 if it is known else unknown. + Noise on antenna 2. Radio link dependent. INT8_MAX: use rx_snr1 if it is known else unknown. + Link quality of serial MAVLink data stream from Rx to Tx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown. + Rssi of antenna 1. 0: no reception. UINT8_MAX: unknown. + Noise on antenna 1. Radio link dependent. INT8_MAX: unknown. + Rssi of antenna 2. 0: no reception. UINT8_MAX: use tx_rssi1 if it is known else unknown. + Noise on antenna 2. Radio link dependent. INT8_MAX: use tx_snr1 if it is known else unknown. + Radio link antenna flags. 0: unknown, assume antenna 1 for all categories. + + Frequency on antenna1 in Hz. 0: unknown. + Frequency on antenna2 in Hz. 0: unknown. +