Skip to content

Commit 3f3c0f1

Browse files
committed
ADSB support for inav over mavlink
1 parent ff6a4bc commit 3f3c0f1

16 files changed

+564
-0
lines changed

.gitignore

+1
Original file line numberDiff line numberDiff line change
@@ -35,3 +35,4 @@ make/local.mk
3535
launch.json
3636
.vscode/tasks.json
3737
.vscode/c_cpp_properties.json
38+
/cmake-build-debug/

docs/Settings.md

+30
Original file line numberDiff line numberDiff line change
@@ -182,6 +182,36 @@ Calculated value after '6 position avanced calibration'. See Wiki page.
182182

183183
---
184184

185+
### adsb_distance_warning
186+
187+
Distance in meters of ADSB aircraft that is displayed
188+
189+
| Default | Min | Max |
190+
| --- |-----| --- |
191+
| 20000 | 1 | 64000 |
192+
193+
---
194+
195+
### adsb_distance_alert
196+
197+
Distance inside which ADSB data flashes for proximity warning
198+
199+
| Default | Min | Max |
200+
| --- |---| --- |
201+
| 3000 | 1 | 64000 |
202+
203+
---
204+
205+
### adsb_ignore_plane_above_me_limit
206+
207+
Ignore adsb planes above, limit, 0 disabled (meters)
208+
209+
| Default | Min | Max |
210+
|---------|-----| --- |
211+
| 0 | 0 | 64000 |
212+
213+
---
214+
185215
### ahrs_acc_ignore_rate
186216

187217
Total gyro rotation rate threshold [deg/s] before scaling to consider accelerometer trustworthy

src/main/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -342,6 +342,7 @@ main_sources(COMMON_SRC
342342
flight/dynamic_lpf.c
343343
flight/dynamic_lpf.h
344344

345+
io/adsb.c
345346
io/beeper.c
346347
io/beeper.h
347348
io/servo_sbus.c

src/main/drivers/osd_symbols.h

+2
Original file line numberDiff line numberDiff line change
@@ -179,6 +179,8 @@
179179
#define SYM_TERRAIN_FOLLOWING 0xFB // 251 Terrain following (also Alt adjust)
180180
#define SYM_CROSS_TRACK_ERROR 0xFC // 252 Cross track error
181181

182+
#define SYM_ADSB 0xFD // 253 ADSB
183+
182184
#define SYM_LOGO_START 0x101 // 257 to 297, INAV logo
183185
#define SYM_LOGO_WIDTH 10
184186
#define SYM_LOGO_HEIGHT 4

src/main/fc/cli.c

+42
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,7 @@ bool cliMode = false;
8585
#include "flight/pid.h"
8686
#include "flight/servos.h"
8787

88+
#include "io/adsb.h"
8889
#include "io/asyncfatfs/asyncfatfs.h"
8990
#include "io/beeper.h"
9091
#include "io/flashfs.h"
@@ -2690,6 +2691,44 @@ static void cliFeature(char *cmdline)
26902691
}
26912692
}
26922693

2694+
#ifdef USE_ADSB
2695+
static void cliAdsbVehicles(char *cmdLine)
2696+
{
2697+
UNUSED(cmdLine);
2698+
2699+
adsbVehicle_t* adsbVehicle;
2700+
adsbVehicle_t* adsbTheClosestVehicle = findVehicleClosest();
2701+
cliPrintf("%-10s%-10s%-10s%-10s%-10s%-16s%-16s%-10s%-14s%-10s%-20s\n", "#", "callsign", "icao", "lat", "lon", " alt (m)", " dist (km)", "dir", "vert dist (m)", "tslc", "ttl", "note");
2702+
2703+
for(uint8_t i = 0; i < MAX_ADSB_VEHICLES; i++){
2704+
adsbVehicle = findVehicle(i);
2705+
if(adsbVehicle != NULL && adsbVehicle->ttl > 0){
2706+
2707+
cliPrintf("%-10d%-10s%-10d%-10u%-10d%-16f%-16f%-10d%-14f%-10d%-10d%-20s \n",
2708+
i,
2709+
adsbVehicle->vehicleValues.callsign,
2710+
adsbVehicle->vehicleValues.icao,
2711+
adsbVehicle->vehicleValues.lat,
2712+
adsbVehicle->vehicleValues.lon,
2713+
(double)CENTIMETERS_TO_METERS(adsbVehicle->vehicleValues.alt),
2714+
(double)CENTIMETERS_TO_METERS(adsbVehicle->calculatedVehicleValues.dist) / 1000,
2715+
adsbVehicle->calculatedVehicleValues.dir,
2716+
(double)CENTIMETERS_TO_METERS(adsbVehicle->calculatedVehicleValues.verticalDistance),
2717+
adsbVehicle->vehicleValues.tslc,
2718+
adsbVehicle->ttl,
2719+
adsbTheClosestVehicle != NULL && adsbTheClosestVehicle->vehicleValues.icao == adsbVehicle->vehicleValues.icao ? "the closest": ""
2720+
);
2721+
}
2722+
}
2723+
2724+
cliPrintf("Messages count from device: %d\n", getAdsbStatus()->vehiclesMessagesTotal);
2725+
2726+
if(!enviromentOkForCalculatingDistaceBearing()){
2727+
cliPrintErrorLine("No GPS FIX, can't calculate distance and direction");
2728+
}
2729+
}
2730+
#endif
2731+
26932732
#ifdef USE_BLACKBOX
26942733
static void printBlackbox(uint8_t dumpMask, const blackboxConfig_t *config, const blackboxConfig_t *configDefault)
26952734
{
@@ -3997,6 +4036,9 @@ const clicmd_t cmdTable[] = {
39974036
#if defined(USE_BOOTLOG)
39984037
CLI_COMMAND_DEF("bootlog", "show boot events", NULL, cliBootlog),
39994038
#endif
4039+
#if defined(USE_ADSB)
4040+
CLI_COMMAND_DEF("adsb_vehicles", "the closest vehicle", NULL, cliAdsbVehicles),
4041+
#endif
40004042
#ifdef USE_LED_STRIP
40014043
CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
40024044
CLI_COMMAND_DEF("mode_color", "configure mode and special colors", NULL, cliModeColor),

src/main/fc/fc_msp.c

+35
Original file line numberDiff line numberDiff line change
@@ -82,6 +82,7 @@
8282
#include "config/config_eeprom.h"
8383
#include "config/feature.h"
8484

85+
#include "io/adsb.h"
8586
#include "io/asyncfatfs/asyncfatfs.h"
8687
#include "io/flashfs.h"
8788
#include "io/gps.h"
@@ -924,6 +925,33 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
924925
sbufWriteU16(dst, gpsSol.epv);
925926
break;
926927
#endif
928+
case MSP2_ADSB_VEHICLE_LIST:
929+
#ifdef USE_ADSB
930+
sbufWriteU8(dst, MAX_ADSB_VEHICLES);
931+
sbufWriteU8(dst, ADSB_CALL_SIGN_MAX_LENGTH);
932+
933+
for(uint8_t i = 0; i < MAX_ADSB_VEHICLES; i++){
934+
935+
adsbVehicle_t *adsbVehicle = findVehicle(i);
936+
937+
for(uint8_t ii = 0; ii < ADSB_CALL_SIGN_MAX_LENGTH; ii++){
938+
sbufWriteU8(dst, adsbVehicle->vehicleValues.callsign[ii]);
939+
}
940+
941+
sbufWriteU32(dst, adsbVehicle->vehicleValues.icao);
942+
sbufWriteU32(dst, adsbVehicle->vehicleValues.lat);
943+
sbufWriteU32(dst, adsbVehicle->vehicleValues.lon);
944+
sbufWriteU32(dst, adsbVehicle->vehicleValues.alt);
945+
sbufWriteU16(dst, (uint16_t)CENTIDEGREES_TO_DEGREES(adsbVehicle->vehicleValues.heading));
946+
sbufWriteU8(dst, adsbVehicle->vehicleValues.tslc);
947+
sbufWriteU8(dst, adsbVehicle->vehicleValues.emitterType);
948+
sbufWriteU8(dst, adsbVehicle->ttl);
949+
}
950+
#else
951+
sbufWriteU8(dst, 0);
952+
sbufWriteU8(dst, 0);
953+
#endif
954+
break;
927955
case MSP_DEBUG:
928956
// output some useful QA statistics
929957
// debug[x] = ((hse_value / 1000000) * 1000) + (SystemCoreClock / 1000000); // XX0YY [crystal clock : core clock]
@@ -1494,6 +1522,13 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
14941522
#else
14951523
sbufWriteU16(dst, 0);
14961524
sbufWriteU16(dst, 0);
1525+
#endif
1526+
#ifdef USE_ADSB
1527+
sbufWriteU16(dst, osdConfig()->adsb_distance_warning);
1528+
sbufWriteU16(dst, osdConfig()->adsb_distance_alert);
1529+
#else
1530+
sbufWriteU16(dst, 0);
1531+
sbufWriteU16(dst, 0);
14971532
#endif
14981533
break;
14991534

src/main/fc/fc_tasks.c

+21
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,7 @@
6868
#include "io/osd_dji_hd.h"
6969
#include "io/displayport_msp_osd.h"
7070
#include "io/servo_sbus.h"
71+
#include "io/adsb.h"
7172

7273
#include "msp/msp_serial.h"
7374

@@ -180,6 +181,14 @@ void taskUpdateCompass(timeUs_t currentTimeUs)
180181
}
181182
#endif
182183

184+
#ifdef USE_ADSB
185+
void taskAdsb(timeUs_t currentTimeUs)
186+
{
187+
UNUSED(currentTimeUs);
188+
adsbTtlClean(currentTimeUs);
189+
}
190+
#endif
191+
183192
#ifdef USE_BARO
184193
void taskUpdateBaro(timeUs_t currentTimeUs)
185194
{
@@ -359,6 +368,9 @@ void fcTasksInit(void)
359368
#ifdef USE_PITOT
360369
setTaskEnabled(TASK_PITOT, sensors(SENSOR_PITOT));
361370
#endif
371+
#ifdef USE_ADSB
372+
setTaskEnabled(TASK_ADSB, true);
373+
#endif
362374
#ifdef USE_RANGEFINDER
363375
setTaskEnabled(TASK_RANGEFINDER, sensors(SENSOR_RANGEFINDER));
364376
#endif
@@ -490,6 +502,15 @@ cfTask_t cfTasks[TASK_COUNT] = {
490502
},
491503
#endif
492504

505+
#ifdef USE_ADSB
506+
[TASK_ADSB] = {
507+
.taskName = "ADSB",
508+
.taskFunc = taskAdsb,
509+
.desiredPeriod = TASK_PERIOD_HZ(1), // ADSB is updated at 1 Hz
510+
.staticPriority = TASK_PRIORITY_IDLE,
511+
},
512+
#endif
513+
493514
#ifdef USE_BARO
494515
[TASK_BARO] = {
495516
.taskName = "BARO",

src/main/fc/settings.yaml

+25
Original file line numberDiff line numberDiff line change
@@ -3359,6 +3359,31 @@ groups:
33593359
max: 11
33603360
default_value: 9
33613361

3362+
- name: osd_adsb_distance_warning
3363+
description: "Distance in meters of ADSB aircraft that is displayed"
3364+
default_value: 20000
3365+
condition: USE_ADSB
3366+
field: adsb_distance_warning
3367+
min: 1
3368+
max: 64000
3369+
type: uint16_t
3370+
- name: osd_adsb_distance_alert
3371+
description: "Distance inside which ADSB data flashes for proximity warning"
3372+
default_value: 3000
3373+
condition: USE_ADSB
3374+
field: adsb_distance_alert
3375+
min: 1
3376+
max: 64000
3377+
type: uint16_t
3378+
- name: osd_adsb_ignore_plane_above_me_limit
3379+
description: "Ignore adsb planes above, limit, 0 disabled (meters)"
3380+
default_value: 0
3381+
condition: USE_ADSB
3382+
field: adsb_ignore_plane_above_me_limit
3383+
min: 0
3384+
max: 64000
3385+
type: uint16_t
3386+
33623387
- name: osd_estimations_wind_compensation
33633388
description: "Use wind estimation for remaining flight time/distance estimation"
33643389
default_value: ON

0 commit comments

Comments
 (0)