Skip to content

Commit

Permalink
ADSB support for inav over mavlink
Browse files Browse the repository at this point in the history
  • Loading branch information
error414 committed Oct 9, 2023
1 parent ff6a4bc commit 3f3c0f1
Show file tree
Hide file tree
Showing 16 changed files with 564 additions and 0 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -35,3 +35,4 @@ make/local.mk
launch.json
.vscode/tasks.json
.vscode/c_cpp_properties.json
/cmake-build-debug/
30 changes: 30 additions & 0 deletions docs/Settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -182,6 +182,36 @@ Calculated value after '6 position avanced calibration'. See Wiki page.

---

### adsb_distance_warning

Distance in meters of ADSB aircraft that is displayed

| Default | Min | Max |
| --- |-----| --- |
| 20000 | 1 | 64000 |

---

### adsb_distance_alert

Distance inside which ADSB data flashes for proximity warning

| Default | Min | Max |
| --- |---| --- |
| 3000 | 1 | 64000 |

---

### adsb_ignore_plane_above_me_limit

Ignore adsb planes above, limit, 0 disabled (meters)

| Default | Min | Max |
|---------|-----| --- |
| 0 | 0 | 64000 |

---

### ahrs_acc_ignore_rate

Total gyro rotation rate threshold [deg/s] before scaling to consider accelerometer trustworthy
Expand Down
1 change: 1 addition & 0 deletions src/main/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -342,6 +342,7 @@ main_sources(COMMON_SRC
flight/dynamic_lpf.c
flight/dynamic_lpf.h

io/adsb.c
io/beeper.c
io/beeper.h
io/servo_sbus.c
Expand Down
2 changes: 2 additions & 0 deletions src/main/drivers/osd_symbols.h
Original file line number Diff line number Diff line change
Expand Up @@ -179,6 +179,8 @@
#define SYM_TERRAIN_FOLLOWING 0xFB // 251 Terrain following (also Alt adjust)
#define SYM_CROSS_TRACK_ERROR 0xFC // 252 Cross track error

#define SYM_ADSB 0xFD // 253 ADSB

#define SYM_LOGO_START 0x101 // 257 to 297, INAV logo
#define SYM_LOGO_WIDTH 10
#define SYM_LOGO_HEIGHT 4
Expand Down
42 changes: 42 additions & 0 deletions src/main/fc/cli.c
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,7 @@ bool cliMode = false;
#include "flight/pid.h"
#include "flight/servos.h"

#include "io/adsb.h"
#include "io/asyncfatfs/asyncfatfs.h"
#include "io/beeper.h"
#include "io/flashfs.h"
Expand Down Expand Up @@ -2690,6 +2691,44 @@ static void cliFeature(char *cmdline)
}
}

#ifdef USE_ADSB
static void cliAdsbVehicles(char *cmdLine)
{
UNUSED(cmdLine);

adsbVehicle_t* adsbVehicle;
adsbVehicle_t* adsbTheClosestVehicle = findVehicleClosest();
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");

for(uint8_t i = 0; i < MAX_ADSB_VEHICLES; i++){
adsbVehicle = findVehicle(i);
if(adsbVehicle != NULL && adsbVehicle->ttl > 0){

cliPrintf("%-10d%-10s%-10d%-10u%-10d%-16f%-16f%-10d%-14f%-10d%-10d%-20s \n",
i,
adsbVehicle->vehicleValues.callsign,
adsbVehicle->vehicleValues.icao,
adsbVehicle->vehicleValues.lat,
adsbVehicle->vehicleValues.lon,
(double)CENTIMETERS_TO_METERS(adsbVehicle->vehicleValues.alt),
(double)CENTIMETERS_TO_METERS(adsbVehicle->calculatedVehicleValues.dist) / 1000,
adsbVehicle->calculatedVehicleValues.dir,
(double)CENTIMETERS_TO_METERS(adsbVehicle->calculatedVehicleValues.verticalDistance),
adsbVehicle->vehicleValues.tslc,
adsbVehicle->ttl,
adsbTheClosestVehicle != NULL && adsbTheClosestVehicle->vehicleValues.icao == adsbVehicle->vehicleValues.icao ? "the closest": ""
);
}
}

cliPrintf("Messages count from device: %d\n", getAdsbStatus()->vehiclesMessagesTotal);

if(!enviromentOkForCalculatingDistaceBearing()){
cliPrintErrorLine("No GPS FIX, can't calculate distance and direction");
}
}
#endif

#ifdef USE_BLACKBOX
static void printBlackbox(uint8_t dumpMask, const blackboxConfig_t *config, const blackboxConfig_t *configDefault)
{
Expand Down Expand Up @@ -3997,6 +4036,9 @@ const clicmd_t cmdTable[] = {
#if defined(USE_BOOTLOG)
CLI_COMMAND_DEF("bootlog", "show boot events", NULL, cliBootlog),
#endif
#if defined(USE_ADSB)
CLI_COMMAND_DEF("adsb_vehicles", "the closest vehicle", NULL, cliAdsbVehicles),
#endif
#ifdef USE_LED_STRIP
CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
CLI_COMMAND_DEF("mode_color", "configure mode and special colors", NULL, cliModeColor),
Expand Down
35 changes: 35 additions & 0 deletions src/main/fc/fc_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,7 @@
#include "config/config_eeprom.h"
#include "config/feature.h"

#include "io/adsb.h"
#include "io/asyncfatfs/asyncfatfs.h"
#include "io/flashfs.h"
#include "io/gps.h"
Expand Down Expand Up @@ -924,6 +925,33 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU16(dst, gpsSol.epv);
break;
#endif
case MSP2_ADSB_VEHICLE_LIST:
#ifdef USE_ADSB
sbufWriteU8(dst, MAX_ADSB_VEHICLES);
sbufWriteU8(dst, ADSB_CALL_SIGN_MAX_LENGTH);

for(uint8_t i = 0; i < MAX_ADSB_VEHICLES; i++){

adsbVehicle_t *adsbVehicle = findVehicle(i);

for(uint8_t ii = 0; ii < ADSB_CALL_SIGN_MAX_LENGTH; ii++){
sbufWriteU8(dst, adsbVehicle->vehicleValues.callsign[ii]);
}

sbufWriteU32(dst, adsbVehicle->vehicleValues.icao);
sbufWriteU32(dst, adsbVehicle->vehicleValues.lat);
sbufWriteU32(dst, adsbVehicle->vehicleValues.lon);
sbufWriteU32(dst, adsbVehicle->vehicleValues.alt);
sbufWriteU16(dst, (uint16_t)CENTIDEGREES_TO_DEGREES(adsbVehicle->vehicleValues.heading));
sbufWriteU8(dst, adsbVehicle->vehicleValues.tslc);
sbufWriteU8(dst, adsbVehicle->vehicleValues.emitterType);
sbufWriteU8(dst, adsbVehicle->ttl);
}
#else
sbufWriteU8(dst, 0);
sbufWriteU8(dst, 0);
#endif
break;
case MSP_DEBUG:
// output some useful QA statistics
// debug[x] = ((hse_value / 1000000) * 1000) + (SystemCoreClock / 1000000); // XX0YY [crystal clock : core clock]
Expand Down Expand Up @@ -1494,6 +1522,13 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
#else
sbufWriteU16(dst, 0);
sbufWriteU16(dst, 0);
#endif
#ifdef USE_ADSB
sbufWriteU16(dst, osdConfig()->adsb_distance_warning);
sbufWriteU16(dst, osdConfig()->adsb_distance_alert);
#else
sbufWriteU16(dst, 0);
sbufWriteU16(dst, 0);
#endif
break;

Expand Down
21 changes: 21 additions & 0 deletions src/main/fc/fc_tasks.c
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@
#include "io/osd_dji_hd.h"
#include "io/displayport_msp_osd.h"
#include "io/servo_sbus.h"
#include "io/adsb.h"

#include "msp/msp_serial.h"

Expand Down Expand Up @@ -180,6 +181,14 @@ void taskUpdateCompass(timeUs_t currentTimeUs)
}
#endif

#ifdef USE_ADSB
void taskAdsb(timeUs_t currentTimeUs)
{
UNUSED(currentTimeUs);
adsbTtlClean(currentTimeUs);
}
#endif

#ifdef USE_BARO
void taskUpdateBaro(timeUs_t currentTimeUs)
{
Expand Down Expand Up @@ -359,6 +368,9 @@ void fcTasksInit(void)
#ifdef USE_PITOT
setTaskEnabled(TASK_PITOT, sensors(SENSOR_PITOT));
#endif
#ifdef USE_ADSB
setTaskEnabled(TASK_ADSB, true);
#endif
#ifdef USE_RANGEFINDER
setTaskEnabled(TASK_RANGEFINDER, sensors(SENSOR_RANGEFINDER));
#endif
Expand Down Expand Up @@ -490,6 +502,15 @@ cfTask_t cfTasks[TASK_COUNT] = {
},
#endif

#ifdef USE_ADSB
[TASK_ADSB] = {
.taskName = "ADSB",
.taskFunc = taskAdsb,
.desiredPeriod = TASK_PERIOD_HZ(1), // ADSB is updated at 1 Hz
.staticPriority = TASK_PRIORITY_IDLE,
},
#endif

#ifdef USE_BARO
[TASK_BARO] = {
.taskName = "BARO",
Expand Down
25 changes: 25 additions & 0 deletions src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3359,6 +3359,31 @@ groups:
max: 11
default_value: 9

- name: osd_adsb_distance_warning
description: "Distance in meters of ADSB aircraft that is displayed"
default_value: 20000
condition: USE_ADSB
field: adsb_distance_warning
min: 1
max: 64000
type: uint16_t
- name: osd_adsb_distance_alert
description: "Distance inside which ADSB data flashes for proximity warning"
default_value: 3000
condition: USE_ADSB
field: adsb_distance_alert
min: 1
max: 64000
type: uint16_t
- name: osd_adsb_ignore_plane_above_me_limit
description: "Ignore adsb planes above, limit, 0 disabled (meters)"
default_value: 0
condition: USE_ADSB
field: adsb_ignore_plane_above_me_limit
min: 0
max: 64000
type: uint16_t

- name: osd_estimations_wind_compensation
description: "Use wind estimation for remaining flight time/distance estimation"
default_value: ON
Expand Down
Loading

0 comments on commit 3f3c0f1

Please sign in to comment.