Skip to content

Commit

Permalink
development.xml: RADIO_LINK statistics messages
Browse files Browse the repository at this point in the history
  • Loading branch information
jlpoltrack committed Mar 3, 2024
1 parent caae60a commit 2bd5847
Showing 1 changed file with 77 additions and 0 deletions.
77 changes: 77 additions & 0 deletions message_definitions/v1.0/development.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,36 @@
<description>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.</description>
</entry>
</enum>
<enum name="RADIO_LINK_STATS_FLAGS" bitmask="true">
<description>RADIO_LINK_STATS flags (bitmask).</description>
<entry value="1" name="RADIO_LINK_STATS_FLAGS_RSSI_DBM">
<description>Rssi values are in negative dBm. Values 0..253 corresponds to 0..-253 dBm. 254 represents no link connection.</description>
</entry>
</enum>
<enum name="RADIO_LINK_TYPE">
<description>RADIO_LINK_TYPE enum.</description>
<entry value="0" name="RADIO_LINK_TYPE_GENERIC">
<description>Unknown radio link type.</description>
</entry>
<entry value="1" name="RADIO_LINK_TYPE_HERELINK">
<description>Radio link is HereLink.</description>
</entry>
<entry value="2" name="RADIO_LINK_TYPE_DRAGONLINK">
<description>Radio link is Dragon Link.</description>
</entry>
<entry value="3" name="RADIO_LINK_TYPE_RFD900">
<description>Radio link is RFD900.</description>
</entry>
<entry value="4" name="RADIO_LINK_TYPE_CROSSFIRE">
<description>Radio link is Crossfire.</description>
</entry>
<entry value="5" name="RADIO_LINK_TYPE_EXPRESSLRS">
<description>Radio link is ExpressLRS.</description>
</entry>
<entry value="6" name="RADIO_LINK_TYPE_MLRS">
<description>Radio link is mLRS.</description>
</entry>
</enum>
</enums>
<messages>
<message id="53" name="MISSION_CHECKSUM">
Expand Down Expand Up @@ -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.</field>
</message>
<message id="421" name="RADIO_LINK_STATS">
<description>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.
</description>
<field type="uint8_t" name="target_system">System ID (ID of target system, normally flight controller).</field>
<field type="uint8_t" name="target_component">Component ID (normally 0 for broadcast).</field>
<field type="uint8_t" name="flags" enum="RADIO_LINK_STATS_FLAGS" display="bitmask">Radio link statistics flags.</field>
<field type="uint8_t" name="rx_LQ_rc" units="c%" invalid="UINT8_MAX">Link quality of RC data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.</field>
<field type="uint8_t" name="rx_LQ_ser" units="c%" invalid="UINT8_MAX">Link quality of serial MAVLink data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.</field>
<field type="uint8_t" name="rx_rssi1" invalid="UINT8_MAX">Rssi of antenna1. 254: no link connection, UINT8_MAX: unknown.</field>
<field type="int8_t" name="rx_snr1" invalid="INT8_MAX">Noise on antenna1. Radio link dependent. INT8_MAX: unknown.</field>
<field type="uint8_t" name="rx_rssi2" invalid="UINT8_MAX">Rssi of antenna2. 254: no link connection, UINT8_MAX: use rx_rssi1 if known else unknown.</field>
<field type="int8_t" name="rx_snr2" invalid="INT8_MAX">Noise on antenna2. Radio link dependent. INT8_MAX: use rx_snr1 if known else unknown.</field>
<field type="uint8_t" name="tx_LQ_ser" units="c%" invalid="UINT8_MAX">Link quality of serial MAVLink data stream from Rx to Tx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.</field>
<field type="uint8_t" name="tx_rssi1" invalid="UINT8_MAX">Rssi of antenna1. 254: no link connection. UINT8_MAX: unknown.</field>
<field type="int8_t" name="tx_snr1" invalid="INT8_MAX">Noise on antenna1. Radio link dependent. INT8_MAX: unknown.</field>
<field type="uint8_t" name="tx_rssi2" invalid="UINT8_MAX">Rssi of antenna2. 254: no link connection. UINT8_MAX: use tx_rssi1 if known else unknown.</field>
<field type="int8_t" name="tx_snr2" invalid="INT8_MAX">Noise on antenna2. Radio link dependent. INT8_MAX: use tx_snr1 if known else unknown.</field>
<field type="uint8_t" name="rx_receive_antenna">0: antenna1, 1: antenna2. If the antenna is not known, assume antenna1.</field>
<field type="uint8_t" name="rx_transmit_antenna">0: antenna1, 1: antenna2. If the antenna is not known, assume antenna1.</field>
<field type="uint8_t" name="tx_receive_antenna">0: antenna1, 1: antenna2. If the antenna is not known, assume antenna1.</field>
<field type="uint8_t" name="tx_transmit_antenna">0: antenna1, 1: antenna2. If the antenna is not known, assume antenna1.</field>
</message>
<message id="422" name="RADIO_LINK_INFORMATION">
<description>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.
</description>
<field type="uint8_t" name="target_system">System ID (ID of target system, normally flight controller).</field>
<field type="uint8_t" name="target_component">Component ID (normally 0 for broadcast).</field>
<field type="uint8_t" name="type" enum="RADIO_LINK_TYPE" invalid="0">Radio link type. 0: unknown/generic type.</field>
<field type="uint8_t" name="mode" invalid="UINT8_MAX">Operation mode. Radio link dependent. UINT8_MAX: ignore/unknown.</field>
<field type="int8_t" name="tx_power" units="dBm" invalid="INT8_MAX">Tx transmit power in dBm. INT8_MAX: unknown.</field>
<field type="int8_t" name="rx_power" units="dBm" invalid="INT8_MAX">Rx transmit power in dBm. INT8_MAX: unknown.</field>
<field type="uint16_t" name="tx_packet_rate" units="Hz" invalid="0">Packet rate in Hz for Tx to Rx transmission. 0: ignore.</field>
<field type="uint16_t" name="rx_packet_rate" units="Hz" invalid="0">Packet rate in Hz for Rx to Tx transmission. Normally equal to tx_packet_rate. 0: ignore.</field>
<field type="uint16_t" name="tx_ser_data_rate" invalid="0">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.</field>
<field type="uint16_t" name="rx_ser_data_rate" invalid="0">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.</field>
<field type="uint8_t" name="tx_receive_sensitivity" invalid="0">Receive sensitivity of Tx in inverted dBm. 1..255 represents -1..-255 dBm, 0: ignore.</field>
<field type="uint8_t" name="rx_receive_sensitivity" invalid="0">Receive sensitivity of Rx in inverted dBm. 1..255 represents -1..-255 dBm, 0: ignore.</field>
</message>
</messages>
</mavlink>

0 comments on commit 2bd5847

Please sign in to comment.