Skip to content

Commit 6cf34fc

Browse files
committed
ADSB CPA calculation
1 parent db16f53 commit 6cf34fc

File tree

10 files changed

+304
-149
lines changed

10 files changed

+304
-149
lines changed

.gitignore

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,3 +46,14 @@ launch.json
4646
# Assitnow token and files for test script
4747
tokens.yaml
4848
*.ubx
49+
/testing/
50+
/.idea/.gitignore
51+
/.idea/.name
52+
/.idea/cmake.xml
53+
/.idea/editor.xml
54+
/.idea/inav.iml
55+
/.idea/runConfigurations/MatekH743.xml
56+
/.idea/misc.xml
57+
/.idea/modules.xml
58+
/.idea/vcs.xml
59+
/.idea/workspace.xml

docs/ADSB.md

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -63,3 +63,41 @@ AT+SETTINGS=SAVE
6363
* in INAV configurator ports TAB set telemetry MAVLINK, and baudrate 115200
6464
* https://pantsforbirds.com/adsbee-1090/quick-start/
6565

66+
---
67+
68+
---
69+
70+
## Alert and Warning
71+
The ADS-B warning/alert system supports two operating modes, controlled by the parameter adsb_calculation_use_cpa (ON or OFF).
72+
73+
---
74+
75+
### ADS-B Warning and Alert Messages (CPA Mode OFF)
76+
The ADS-B warning/alert system supports two operating modes, controlled by the parameter **adsb_calculation_use_cpa** (ON or OFF).
77+
78+
When **adsb_calculation_use_cpa = OFF**, the system evaluates only the **current distance between the aircraft and the UAV**. The aircraft with the **shortest distance** is always selected for monitoring.
79+
80+
- If the aircraft enters the **warning zone** (`adsb_distance_warning`), the corresponding **OSD element is displayed**.
81+
- If the aircraft enters the **alert zone** (`adsb_distance_alert`), the **OSD element starts blinking**, indicating a higher-priority alert.
82+
83+
This mode therefore provides a simple proximity-based warning determined purely by real-time distance.
84+
85+
---
86+
87+
### ADS-B Warning and Alert Messages (CPA Mode ON)
88+
89+
When **adsb_calculation_use_cpa = ON**, the system evaluates aircraft using the **Closest Point of Approach (CPA)** and predicted trajectories, not only the current distance.
90+
91+
1. **Aircraft already inside the alert zone**
92+
If one or more aircraft are currently inside the **alert zone** (`adsb_distance_alert`), the **closest aircraft** to the UAV is selected and the **OSD element blinks**.
93+
94+
2. **Aircraft in the warning zone, none predicted to enter the alert zone**
95+
If aircraft are present in the **warning zone** (`adsb_distance_warning`), but none of them are predicted to enter the **alert zone** (their CPA distance is greater than `adsb_distance_alert`), the **closest aircraft to the UAV** is selected and the **OSD element remains steady** (no blinking).
96+
97+
3. **Aircraft in the warning zone, one predicted to enter the alert zone**
98+
If at least one aircraft in the **warning zone** is predicted to enter the **alert zone**, that aircraft is selected and the **OSD element blinks**.
99+
100+
4. **Aircraft in the warning zone, multiple predicted to enter the alert zone**
101+
If multiple aircraft are predicted to enter the **alert zone**, the system selects the aircraft that will **reach the alert zone first**, and the **OSD element blinks**.
102+
103+
![ADSB CPA_ON](assets/images/adsb-CPA-on.png)

docs/assets/images/adsb-CPA-on.png

382 KB
Loading

src/main/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -358,6 +358,7 @@ main_sources(COMMON_SRC
358358
flight/adaptive_filter.h
359359

360360
io/adsb.c
361+
io/adsb.h
361362
io/beeper.c
362363
io/beeper.h
363364
io/servo_sbus.c

src/main/fc/fc_tasks.c

Lines changed: 1 addition & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -187,14 +187,6 @@ void taskUpdateCompass(timeUs_t currentTimeUs)
187187
}
188188
#endif
189189

190-
#ifdef USE_ADSB
191-
void taskAdsb(timeUs_t currentTimeUs)
192-
{
193-
UNUSED(currentTimeUs);
194-
adsbTtlClean(currentTimeUs);
195-
}
196-
#endif
197-
198190
#ifdef USE_BARO
199191
void taskUpdateBaro(timeUs_t currentTimeUs)
200192
{
@@ -554,7 +546,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
554546
[TASK_ADSB] = {
555547
.taskName = "ADSB",
556548
.taskFunc = taskAdsb,
557-
.desiredPeriod = TASK_PERIOD_HZ(1), // ADSB is updated at 1 Hz
549+
.desiredPeriod = TASK_PERIOD_MS(500), // ADSB is updated at 1 Hz
558550
.staticPriority = TASK_PRIORITY_IDLE,
559551
},
560552
#endif

src/main/fc/settings.yaml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3677,6 +3677,12 @@ groups:
36773677
field: adsb_warning_style
36783678
type: uint8_t
36793679
condition: USE_ADSB
3680+
- name: osd_adsb_calculation_use_cpa
3681+
description: "Use CPA (Closest Point of Approach) method for ADS-B traffic distance and collision risk calculation instead of instantaneous distance."
3682+
default_value: OFF
3683+
field: adsb_calculation_use_cpa
3684+
type: bool
3685+
condition: USE_ADSB
36803686
- name: osd_estimations_wind_compensation
36813687
description: "Use wind estimation for remaining flight time/distance estimation"
36823688
default_value: ON

0 commit comments

Comments
 (0)