Skip to content

Commit 5e434e6

Browse files
committed
* add ADSB simulator script to inject ADSB contact to FC for devel purpose
* update settings.md * MSP2 return ADSB limits, and warning/alert vehicle ICAO * ADSB CPA calculation
1 parent 94fd8cb commit 5e434e6

File tree

17 files changed

+564
-150
lines changed

17 files changed

+564
-150
lines changed

.gitignore

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,8 @@ launch.json
4646
# Assitnow token and files for test script
4747
tokens.yaml
4848
*.ubx
49+
/testing/
50+
/.idea/
4951

5052
# Local development files
5153
.semgrepignore

dev/adsb/adsb_uart_sender.py

Lines changed: 82 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,82 @@
1+
import json
2+
import time
3+
import argparse
4+
import serial
5+
from pymavlink.dialects.v20 import common as mavlink2
6+
7+
def load_aircraft(json_file):
8+
with open(json_file, "r") as f:
9+
return json.load(f)
10+
11+
def create_mavlink(serial_port):
12+
mav = mavlink2.MAVLink(serial_port)
13+
mav.srcSystem = 1
14+
mav.srcComponent = mavlink2.MAV_COMP_ID_ADSB
15+
return mav
16+
17+
def send_heartbeat(mav):
18+
mav.heartbeat_send(
19+
mavlink2.MAV_TYPE_ADSB,
20+
mavlink2.MAV_AUTOPILOT_INVALID,
21+
0,
22+
0,
23+
0
24+
)
25+
26+
def send_adsb(mav, aircraft):
27+
for ac in aircraft:
28+
icao = int(ac["icao_address"])
29+
lat = int(ac["lat"] * 1e7)
30+
lon = int(ac["lon"] * 1e7)
31+
alt_mm = int(ac["altitude"] * 1000)
32+
heading_cdeg = int(ac["heading"] * 100)
33+
hor_vel_cms = int(ac["hor_velocity"] * 100)
34+
ver_vel_cms = int(ac["ver_velocity"] * 100)
35+
callsign = ac["callsign"].encode("ascii").ljust(9, b'\x00')
36+
37+
msg = mavlink2.MAVLink_adsb_vehicle_message(
38+
ICAO_address=icao,
39+
lat=lat,
40+
lon=lon,
41+
altitude_type=0,
42+
altitude=alt_mm,
43+
heading=heading_cdeg,
44+
hor_velocity=hor_vel_cms,
45+
ver_velocity=ver_vel_cms,
46+
callsign=callsign,
47+
emitter_type=0,
48+
tslc=1,
49+
flags=3,
50+
squawk=0
51+
)
52+
53+
mav.send(msg)
54+
55+
def main():
56+
parser = argparse.ArgumentParser()
57+
parser.add_argument("com_port")
58+
parser.add_argument("json_file")
59+
parser.add_argument("--baud", default=115200, type=int)
60+
parser.add_argument("--rate", default=1.0, type=float)
61+
args = parser.parse_args()
62+
63+
ser = serial.Serial(args.com_port, args.baud)
64+
mav = create_mavlink(ser)
65+
66+
aircraft = load_aircraft(args.json_file)
67+
68+
period = 1.0 / args.rate
69+
last_hb = 0
70+
71+
while True:
72+
now = time.time()
73+
74+
if now - last_hb >= 1.0:
75+
send_heartbeat(mav)
76+
last_hb = now
77+
78+
send_adsb(mav, aircraft)
79+
time.sleep(period)
80+
81+
if __name__ == "__main__":
82+
main()

dev/adsb/aircraft.json

Lines changed: 52 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
1+
[
2+
{
3+
"icao_address": 1002,
4+
"lat": 49.2341564,
5+
"lon": 16.5505527,
6+
"altitude": 300,
7+
"heading": 275,
8+
"hor_velocity": 30,
9+
"ver_velocity": 0,
10+
"callsign": "V550"
11+
},
12+
{
13+
"icao_address": 1001,
14+
"lat": 49.2344299,
15+
"lon": 16.5610206,
16+
"altitude": 300,
17+
"heading": 237,
18+
"hor_velocity": 30,
19+
"ver_velocity": 0,
20+
"callsign": "V250"
21+
},
22+
{
23+
"icao_address": 1003,
24+
"lat": 49.2422463,
25+
"lon": 16.5645653,
26+
"altitude": 300,
27+
"heading": 29,
28+
"hor_velocity": 30,
29+
"ver_velocity": 0,
30+
"callsign": "V1100"
31+
},
32+
{
33+
"icao_address": 1004,
34+
"lat": 49.2377083,
35+
"lon": 16.5520834,
36+
"altitude": 300,
37+
"heading": 110,
38+
"hor_velocity": 30,
39+
"ver_velocity": 0,
40+
"callsign": "V650X3"
41+
},
42+
{
43+
"icao_address": 1005,
44+
"lat": 49.2388158,
45+
"lon": 16.5730266,
46+
"altitude": 300,
47+
"heading": 261,
48+
"hor_velocity": 30,
49+
"ver_velocity": 0,
50+
"callsign": "V1250X4"
51+
}
52+
]

dev/adsb/readme.md

Lines changed: 87 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,87 @@
1+
# ADSB Vehicle MAVLink Simulator
2+
3+
A Python tool for simulating ADS-B aircraft traffic over a serial connection using the MAVLink protocol. Useful for testing ADS-B receivers, ground station software, or flight controller integrations without real aircraft.
4+
5+
---
6+
7+
## Requirements
8+
```bash
9+
pip install pymavlink pyserial
10+
```
11+
12+
---
13+
14+
## Usage
15+
```bash
16+
python adsb_sim.py <com_port> <json_file> [--baud BAUD] [--rate RATE]
17+
```
18+
19+
### Arguments
20+
21+
| Argument | Required | Default | Description |
22+
|---|---|---|---|
23+
| `com_port` ||| Serial port (e.g. `COM3`, `/dev/ttyUSB0`) |
24+
| `json_file` ||| Path to JSON file with aircraft definitions |
25+
| `--baud` || `115200` | Serial baud rate |
26+
| `--rate` || `1.0` | Update rate in Hz |
27+
28+
### Examples
29+
```bash
30+
# Windows
31+
python adsb_sim.py COM3 aircraft.json
32+
33+
# Linux
34+
python adsb_sim.py /dev/ttyUSB0 aircraft.json --baud 57600 --rate 2.0
35+
```
36+
37+
---
38+
39+
## Aircraft JSON Format
40+
41+
Each aircraft is defined as an object in a JSON array:
42+
```json
43+
[
44+
{
45+
"icao_address": 1001,
46+
"lat": 49.2344299,
47+
"lon": 16.5610206,
48+
"altitude": 300,
49+
"heading": 237,
50+
"hor_velocity": 30,
51+
"ver_velocity": 0,
52+
"callsign": "V250"
53+
}
54+
]
55+
```
56+
57+
| Field | Type | Unit | Description |
58+
|---|---|---|---|
59+
| `icao_address` | int || Unique ICAO identifier |
60+
| `lat` | float | degrees | Latitude |
61+
| `lon` | float | degrees | Longitude |
62+
| `altitude` | float | meters ASL | Altitude above sea level |
63+
| `heading` | float | degrees (0–360) | Track heading |
64+
| `hor_velocity` | float | m/s | Horizontal speed |
65+
| `ver_velocity` | float | m/s | Vertical speed (positive = climb) |
66+
| `callsign` | string || Aircraft callsign (max 8 chars) |
67+
68+
---
69+
70+
## How It Works
71+
72+
The simulator connects to a serial port and continuously transmits two MAVLink message types:
73+
74+
- **HEARTBEAT** — sent once per second to identify the component as an ADS-B device
75+
- **ADSB_VEHICLE** — sent for each aircraft at the configured rate, containing position, velocity, heading and identification data
76+
77+
All aircraft from the JSON file are broadcast in every update cycle. The positions are static — aircraft do not move between updates.
78+
79+
---
80+
81+
## Notes
82+
83+
- Altitude is transmitted in millimeters internally (`altitude * 1000`) as required by the MAVLink `ADSB_VEHICLE` message spec
84+
- Heading is transmitted in centidegrees (`heading * 100`)
85+
- Callsigns are ASCII-encoded and null-padded to 9 bytes
86+
- `flags` is set to `3` (lat/lon and altitude valid)
87+
- `tslc` (time since last communication) is hardcoded to `1` second

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/Settings.md

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4482,6 +4482,16 @@ Optical flow module scale factor
44824482

44834483
---
44844484

4485+
### osd_adsb_calculation_use_cpa
4486+
4487+
Use CPA (Closest Point of Approach) method for ADS-B traffic distance and collision risk calculation instead of instantaneous distance.
4488+
4489+
| Default | Min | Max |
4490+
| --- | --- | --- |
4491+
| OFF | OFF | ON |
4492+
4493+
---
4494+
44854495
### osd_adsb_distance_alert
44864496

44874497
Distance inside which ADSB data flashes for proximity warning

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
@@ -360,6 +360,7 @@ main_sources(COMMON_SRC
360360
flight/adaptive_filter.h
361361

362362
io/adsb.c
363+
io/adsb.h
363364
io/beeper.c
364365
io/beeper.h
365366
io/servo_sbus.c

src/main/fc/fc_msp.c

Lines changed: 43 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1042,6 +1042,49 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
10421042
sbufWriteU8(dst, 0);
10431043
sbufWriteU32(dst, 0);
10441044
sbufWriteU32(dst, 0);
1045+
#endif
1046+
break;
1047+
case MSP2_ADSB_LIMITS:
1048+
#ifdef USE_ADSB
1049+
sbufWriteU16(dst, osdConfig()->adsb_distance_warning);
1050+
sbufWriteU16(dst, osdConfig()->adsb_distance_alert);
1051+
sbufWriteU16(dst, osdConfig()->adsb_ignore_plane_above_me_limit);
1052+
#else
1053+
sbufWriteU16(dst, 0);
1054+
sbufWriteU16(dst, 0);
1055+
sbufWriteU16(dst, 0);
1056+
#endif
1057+
break;
1058+
case MSP2_ADSB_WARNING_VEHICLE_ICAO:
1059+
#ifdef USE_ADSB
1060+
if(isEnvironmentOkForCalculatingADSBDistanceBearing()) {
1061+
adsbVehicle_t *vehicle = NULL;
1062+
bool isAlert = true;
1063+
vehicle = findVehicleForAlert(
1064+
METERS_TO_CENTIMETERS(osdConfig()->adsb_distance_alert),
1065+
METERS_TO_CENTIMETERS(osdConfig()->adsb_distance_warning),
1066+
METERS_TO_CENTIMETERS(osdConfig()->adsb_ignore_plane_above_me_limit)
1067+
);
1068+
1069+
if(vehicle == NULL) {
1070+
vehicle = findVehicleForWarning(METERS_TO_CENTIMETERS(osdConfig()->adsb_distance_warning), METERS_TO_CENTIMETERS(osdConfig()->adsb_ignore_plane_above_me_limit));
1071+
isAlert = false;
1072+
}
1073+
1074+
if(vehicle != NULL) {
1075+
sbufWriteU32(dst, vehicle->vehicleValues.icao);
1076+
sbufWriteU8(dst, isAlert ? 1 : 0);;
1077+
} else {
1078+
sbufWriteU32(dst, 0);
1079+
sbufWriteU8(dst, 0);;
1080+
}
1081+
} else {
1082+
sbufWriteU32(dst, 0);
1083+
sbufWriteU8(dst, 0);
1084+
}
1085+
#else
1086+
sbufWriteU32(dst, 0);
1087+
sbufWriteU8(dst, 0);
10451088
#endif
10461089
break;
10471090
case MSP_DEBUG:

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

0 commit comments

Comments
 (0)