Testing INAV's ADSB functions - stronnag/mwptools GitHub Wiki

Testing INAV's ADSB functions

Introduction

From INAV (7.1?), it is possible to receive general aviation (GA) Automatic Dependent Surveillance–Broadcast (ADSB) reports to the flight controller and shown on the OSD.

It is also possible to interrogate the FC and display this data in mwp or other MSP capable GCS that implements MSP2_ADSB_VEHICLE_LIST. mwp provides this capability and it will also be available in the INAV Configurator 8.0 (globally; it probably worked in 7.1.1 if the aircraft was east of the prime meridian and north of the equator).

Requirements

  • Vehicle fitted with PingRX or TT-SC1 ADSB receiver (or simulated as described below)
  • INAV UART configured to receive MAVlink telemetry
  • GCS that can poll for MSP2_ADSB_VEHICLE_LIST.

Caveats

  • If you want ADSB on your ground station, a ground based solution may work much better in terms of displayed GA picture.
  • The MSP2_ADSB_VEHICLE_LIST message is 152 bytes, regardless of whether any aircraft are in view. This may be challenging for low bandwidth / low capability down links.
  • MSP2_ADSB_VEHICLE_LIST can report at most 5 aircraft.

Simulating and testing

The capability can be tested by sending a stream of Mavlink ADSB_VEHICLE messages to a Mavlink enabled UART on either a flight controller or the SITL. In the rest of this article, the SITL is used for convenience.

SITL Testing

  • The SITL is configured with the following ports
serial 1 1 115200 115200 0 115200
# MAVlink for MAVlink ADSB messages (e.g PingRX, TT-SC1)
serial 6 256 115200 115200 0 115200
# Optional ..
serial 7 17 115200 115200 0 115200
  • mwp or the INAV Configurator connects to tcp://localhost:5760

  • Simulated ADSL / MAVlink TRAFFIC REPORT / ADSB VEHICLE data is provided to the SITL MAVLink port by:

mwp-mavlink-traffic-sim -d tcp://localhost:5766 -c 54.355193,-4.523159
##### The `-c` option defines the centre of the swarm, you can use any location.
mwp-log-replay -d tcp://localhost:5766 jurby-mav-adsb.rawlog

Note: The SITL is used for convenience only (vice a real FC).

Invoking the SITL

The SITL is started by the following script, using the default rebase (54.355193,-4.523159), for convenience with fl2sitl to provide a full set of simulated sensors.

 #!/usr/bin/env bash

EEPROM=${EEPROM:-fw-eeprom-fwa.bin}
REBASE=

if [ "$#" -eq 2 ] ; then
   REBASE="--rebase $1,$2"
elif [ "$#" -eq 1 ] ; then
  LN=$(grep -i $1 ~/.config/mwp/places)
  LAT=$(echo $LN | cut -f 2 -d ' ')
  LON=$(echo $LN | cut -f 3 -d ' ')
  REBASE="--rebase $LAT,$LON"
else
  REBASE="--rebase 54.355193,-4.523159"
fi
[ "$REBASE" = "--rebase " ] && REBASE=
echo $REBASE
(fl2sitl --minimal $REBASE &) && inav_SITL --path ~/.config/sitl/$EEPROM --sim xp

Sample Output

Various aircraft (and a balloon).

Screenshot from 2024-05-19 12-48-51

Note: mwp is polling the SITL with MSP2_ADSB_VEHICLE_LIST to obtain the ADSB contacts.

Validating captured data

If you capture MAVLink ADSB_VEHICLE data using mwp-serial-cap, you can validate the date using mwptools' mavreader tool:

$ mavreader mav-adsb.rawlog
...
0602.09 < Mav1: mavlink_traffic_report 38 : ICAO 9c6150, callsign TEST00140 valid 13f : 55.227637 -5.025020 9051.0m af=both 308° 308m/s etyp 0, tslc 6
0602.12 < Mav1: mavlink_traffic_report 38 : ICAO 9c6190, callsign TEST00141 valid 13f : 55.040617 -6.396279 6295.0m af=both 284° 284m/s etyp 1, tslc 8
0602.15 < Mav1: mavlink_traffic_report 38 : ICAO 9c61d0, callsign TEST00142 valid 13f : 55.800711 -5.467041 10584.0m af=both 345° 345m/s etyp 2, tslc 6
0602.17 < Mav1: mavlink_traffic_report 38 : ICAO 9c6210, callsign TEST00143 valid 13f : 53.154437 -3.781402 12809.0m af=both 153° 153m/s etyp 3, tslc 7