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 Dec 17, 2023
1 parent 0535617 commit 874407b
Show file tree
Hide file tree
Showing 16 changed files with 565 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/
17 changes: 17 additions & 0 deletions docs/ADSB.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
# ADS-B

[Automatic Dependent Surveillance Broadcast](https://en.wikipedia.org/wiki/Automatic_Dependent_Surveillance%E2%80%93Broadcast)
is an air traffic surveillance technology that enables aircraft to be accurately tracked by air traffic controllers and other pilots without the need for conventional radar.

## Current state

OSD can be configured to shows the closest aircraft.

## Hardware

All ADSB receivers which can send Mavlink [ADSB_VEHICLE](https://mavlink.io/en/messages/common.html#ADSB_VEHICLE) message are supported

* [PINGRX](https://uavionix.com/product/pingrx-pro/) (not tested)
* [TT-SC1](https://www.aerobits.pl/product/aero/) (tested)


30 changes: 30 additions & 0 deletions docs/Settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -4002,6 +4002,36 @@ _// TODO_

---

### osd_adsb_distance_alert

Distance inside which ADSB data flashes for proximity warning

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

---

### osd_adsb_distance_warning

Distance in meters of ADSB aircraft that is displayed

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

---

### osd_adsb_ignore_plane_above_me_limit

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

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

---

### osd_ahi_bordered

Shows a border/corners around the AHI region (pixel OSD only)
Expand Down
1 change: 1 addition & 0 deletions src/main/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -344,6 +344,7 @@ main_sources(COMMON_SRC
flight/ez_tune.c
flight/ez_tune.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 @@ -180,6 +180,8 @@
#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
35 changes: 35 additions & 0 deletions src/main/fc/fc_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,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 @@ -948,6 +949,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 @@ -1518,6 +1546,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 @@ -69,6 +69,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 @@ -181,6 +182,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 @@ -360,6 +369,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 @@ -495,6 +507,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 @@ -3444,6 +3444,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 874407b

Please sign in to comment.