diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index aeceaff67e..058c5f80e3 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -23,6 +23,36 @@ 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 0..253 corresponds to 0..-253 dBm. 254 represents no link connection. + + + + RADIO_LINK_TYPE enum. + + Unknown radio link type. + + + Radio link is HereLink. + + + Radio link is Dragon Link. + + + Radio link is RFD900. + + + Radio link is Crossfire. + + + Radio link is ExpressLRS. + + + Radio link is mLRS. + + @@ -71,5 +101,52 @@ 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. Tx: ground-side device, Rx: vehicle-side device. + The message is normally emitted upon each receiption of a data packet on the link. + 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 units are inverted dBm: 0..253 correspond to 0..-253 dBm, 254 represents no link connection. + 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 antenna1. 254: no link connection, UINT8_MAX: unknown. + Noise on antenna1. Radio link dependent. INT8_MAX: unknown. + Rssi of antenna2. 254: no link connection, UINT8_MAX: use rx_rssi1 if known else unknown. + Noise on antenna2. Radio link dependent. INT8_MAX: use rx_snr1 if 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 antenna1. 254: no link connection. UINT8_MAX: unknown. + Noise on antenna1. Radio link dependent. INT8_MAX: unknown. + Rssi of antenna2. 254: no link connection. UINT8_MAX: use tx_rssi1 if known else unknown. + Noise on antenna2. Radio link dependent. INT8_MAX: use tx_snr1 if known else unknown. + 0: antenna1, 1: antenna2. If the antenna is not known, assume antenna1. + 0: antenna1, 1: antenna2. If the antenna is not known, assume antenna1. + 0: antenna1, 1: antenna2. If the antenna is not known, assume antenna1. + 0: antenna1, 1: antenna2. If the antenna is not known, assume antenna1. + + + Radio link information. Tx: ground-side device, Rx: vehicle-side device. + The values of the fields in this message do normally not or only slowly change with time, and for most times the message can be send at a low rate, like 0.2 Hz. + If values change then the message should temporarily be send more often to inform the system about the changes. + 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 type. 0: unknown/generic type. + Operation mode. Radio link dependent. UINT8_MAX: ignore/unknown. + Tx transmit power in dBm. INT8_MAX: unknown. + Rx transmit power in dBm. INT8_MAX: unknown. + Packet rate in Hz for Tx to Rx transmission. 0: ignore. + Packet rate in Hz for Rx to Tx transmission. Normally equal to tx_packet_rate. 0: ignore. + Data rate of serial stream in Bytes/s for Tx to Rx transmission. 0: ignore. UINT16_MAX: data rate is 64 KBytes/s or larger. + Data rate of serial stream in Bytes/s for Rx to Tx transmission. 0: ignore. UINT16_MAX: data rate is 64 KBytes/s or larger. + Receive sensitivity of Tx in inverted dBm. 1..255 represents -1..-255 dBm, 0: ignore. + Receive sensitivity of Rx in inverted dBm. 1..255 represents -1..-255 dBm, 0: ignore. +