Skip to content

Commit 8faaabe

Browse files
committed
Initial version of MAVlink output AIRDOS03 variant.
1 parent afdb076 commit 8faaabe

3 files changed

Lines changed: 937 additions & 112 deletions

File tree

fw/AIRDOS03_MAVLink/README.md

Lines changed: 216 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,224 @@
1-
# AIRDOS firwware suitable to connection MAVlink-based UAV platform
1+
# AIRDOS03 MAVLink Firmware
22

3-
The firmware outputs [MAVLink messages](https://en.wikipedia.org/wiki/MAVLink) suitable to interfacing to [TF-ATMON](https://docs.thunderfly.cz/instruments/TF-ATMON) system.
3+
MAVLink tunnel-based firmware for AIRDOS03B on TFUNIPAYLOAD01 (ATmega1284P, 8 MHz). Functionally equivalent to `fw/AIRDOS03_USTDFF` but transmits data as binary MAVLink TUNNEL packets instead of ASCII text, suitable for integration with [TF-ATMON](https://docs.thunderfly.cz/instruments/TF-ATMON) and PX4/ArduPilot autopilots.
44

5-
### Loading compiled binaries to MCU
5+
## Build and upload
66

7+
```
8+
source ~/.venv/bin/activate
9+
pio run -e TFUNIPAYLOAD01_uart -t upload
10+
```
11+
12+
Using avrdude directly:
13+
```
14+
avrdude -v -patmega1284p -carduino -P/dev/ttyUSB0 -b57600 -D -Uflash:w:firmware.hex:i
15+
```
16+
17+
## Decode to text format
18+
19+
```
20+
pip install pymavlink
21+
python tools/mavlink_to_airdos.py --port /dev/ttyUSB0 --baud 115200
22+
python tools/mavlink_to_airdos.py --stdin < capture.bin
23+
```
24+
25+
Output is AIRDOS04-compatible ASCII format (same as `fw/AIRDOS03_USTDFF`).
26+
27+
28+
## MAVLink Packet Protocol
29+
30+
All packets use TUNNEL message (`payload_type = 4`, sensor ID for AIRDOS03B).
31+
The message sub-type is encoded as **byte 0** of the 128-byte payload.
32+
33+
```cpp
34+
SendTunnelData(buf, len, 4, 1, 1); // same payload_type for all AIRDOS03B messages
35+
```
36+
37+
All multi-byte integers are **little-endian**.
38+
39+
### Message sub-types
40+
41+
| Byte 0 | Name | Corresponds to | Payload size |
42+
|--------|-----------------|-------------------|--------------|
43+
| 0x01 | AIRDOS_STARTUP | `$DOS` + `$ADC` | 29 B |
44+
| 0x02 | AIRDOS_TIMESYNC | `$TIME` | 18 B |
45+
| 0x03 | AIRDOS_START | `$START` | 5 B |
46+
| 0x04 | AIRDOS_STOP | `$STOP` header | 14 B |
47+
| 0x05 | AIRDOS_HIST_LO | histogram[0..31] | 69 B |
48+
| 0x06 | AIRDOS_HIST_HI | histogram[32..63] | 67 B |
49+
| 0x07 | AIRDOS_EVENTS | `$E` events | ≤121 B |
50+
| 0x08 | AIRDOS_ENV | `$ENV` | 17 B |
51+
52+
---
53+
54+
### 0x01 — STARTUP (29 bytes)
55+
56+
Sent once at startup. Provides device identification (`$DOS`, `$ADC`).
57+
58+
```
59+
Offset Size Field
60+
0 1 sub_type = 0x01
61+
1 1 threshold // THRESHOLD constant (64)
62+
2 2 max_events // MAX_EVENTS constant (300)
63+
4 16 serial_number // raw bytes from EEPROM 0x5B offset 0x0800
64+
20 1 adc_conf1 // from EEPROM 0x53 offset 0x0000
65+
21 1 adc_conf2 // from EEPROM 0x53 offset 0x0001
66+
22 1 fw_major // MAJOR version
67+
23 1 fw_minor // MINOR version
68+
24 4 reserved // zero
69+
```
70+
71+
Python: `struct.unpack_from('<BBH16sBBBB4s', payload)`
72+
73+
---
74+
75+
### 0x02 — TIMESYNC (18 bytes)
76+
77+
Sent on first GNSS fix and on re-sync after fix loss (`$TIME`).
78+
79+
```
80+
Offset Size Field
81+
0 1 sub_type = 0x02
82+
1 1 gnss_synced // 1 = valid GNSS fix, 0 = not synced
83+
2 4 rtc_seconds // 1PPS-derived seconds counter
84+
6 4 gnss_sync_unix // Unix time from last valid $GNRMC
85+
10 4 current_unix // gnss_sync_unix + (rtc_seconds - sync_rtc_seconds)
86+
14 4 sync_age // seconds since last GNSS fix
87+
```
88+
89+
Python: `struct.unpack_from('<BB4I', payload)`
90+
91+
---
92+
93+
### 0x03 — START (5 bytes)
94+
95+
Sent at start of each 10 s integration window (`$START`).
96+
97+
```
98+
Offset Size Field
99+
0 1 sub_type = 0x03
100+
1 2 count // measurement cycle index
101+
3 2 start_systime // TCNT1 at start of window (128 µs/tick)
102+
```
103+
104+
Python: `struct.unpack_from('<BHH', payload)`
105+
106+
---
107+
108+
### 0x04 — STOP (14 bytes)
109+
110+
Sent after events, before histogram packets (`$STOP` header fields).
111+
112+
```
113+
Offset Size Field
114+
0 1 sub_type = 0x04
115+
1 2 count // same cycle index as START
116+
3 4 tm // Unix time at end of window (0 if not synced)
117+
7 1 tm_s100 // hundredths of second (0–99)
118+
8 2 stop_systime // TCNT1 at end of window
119+
10 2 events_total // total events_counter (may exceed MAX_EVENTS)
120+
12 2 events_sent // min(events_total, MAX_EVENTS)
121+
```
122+
123+
Python: `struct.unpack_from('<B H I B H H H', payload)` (no padding)
124+
125+
---
126+
127+
### 0x05 — HIST_LO (69 bytes) and 0x06 — HIST_HI (67 bytes)
128+
129+
64-channel uint16 histogram split across two packets (lossless). Together they form
130+
the histogram fields of `$STOP`.
131+
132+
```
133+
HIST_LO (0x05): HIST_HI (0x06):
134+
Offset Size Field Offset Size Field
135+
0 1 sub_type = 0x05 0 1 sub_type = 0x06
136+
1 2 count 1 2 count
137+
3 64 hist[0..31] 3 64 hist[32..63]
138+
(32 × uint16) (32 × uint16)
139+
```
140+
141+
Python: `struct.unpack_from('<BH32H', payload)`
142+
143+
---
144+
145+
### 0x07 — EVENTS (≤121 bytes, chunked)
146+
147+
Up to 29 events per packet. Sent only if `events_sent > 0`.
148+
Multiple packets with `chunk_index` 0 … `chunk_total − 1`. Each event → one `$E` line.
149+
150+
```
151+
Offset Size Field
152+
0 1 sub_type = 0x07
153+
1 2 count // cycle index
154+
3 1 chunk_index // 0-based
155+
4 1 chunk_total // total chunks for this cycle
156+
5 1 events_in_chunk // events in this packet (1–29)
157+
6 3 reserved
158+
9 events_in_chunk × 4:
159+
uint16 event_time // TCNT1 (128 µs/tick)
160+
uint16 event_channel // ADC value ≥ THRESHOLD (64)
161+
```
162+
163+
Max: 9 + 29 × 4 = 125 B. For 300 events: ceil(300/29) = 11 packets.
164+
165+
Python header: `struct.unpack_from('<BHBBBxxx', payload[:9])`
166+
Python events: `struct.unpack_from(f'<{2*n}H', payload[9:9+n*4])` — pairs (time, channel)
167+
168+
---
169+
170+
### 0x08 — ENV (17 bytes)
171+
172+
Sent at startup and every 30 s (`$ENV`).
173+
174+
```
175+
Offset Size Field
176+
0 1 sub_type = 0x08
177+
1 2 count // measurement cycle index
178+
3 4 tm // Unix time (0 if not synced)
179+
7 1 tm_s100 // hundredths of second
180+
8 1 reserved
181+
9 4 temperature // float32, °C (IEEE 754 single, little-endian)
182+
13 4 humidity // float32, % RH
183+
```
184+
185+
Python: `struct.unpack_from('<BHIBxff', payload)`
186+
187+
---
188+
189+
## Emission sequence
190+
191+
```
192+
At setup():
193+
STARTUP (0x01)
194+
ENV (0x08) ← initial sensor reading
195+
196+
Every 10 s:
197+
START (0x03)
198+
EVENTS (0x07) × N chunks (omitted if events_sent == 0)
199+
STOP (0x04)
200+
HIST_LO (0x05)
201+
HIST_HI (0x06)
202+
203+
Every 30 s (in addition to measurement cycle):
204+
ENV (0x08)
205+
206+
On GNSS fix or re-sync after fix loss:
207+
TIMESYNC (0x02)
208+
```
209+
210+
---
7211
8-
#### Avrdude
212+
## Decoder output format
9213
10-
In case of using the avrdude and mightyCore bootloader we should use following command:
214+
`tools/mavlink_to_airdos.py` reconstructs AIRDOS04-compatible text:
11215
12216
```
13-
avrdude -v -patmega1284p -carduino -P/dev/ttyUSB0 -b57600 -D -Uflash:w:/tmp/arduino_build_743311/LABDOS.ino.hex:i
217+
$DOS,AIRDOS03B,<major>.<minor>,0,unknown,MAVLink,<sn_hex_32chars>
218+
$ADC,USTSIPIN03C,<sn_hex_32chars>,<conf1hex><conf2hex>
219+
$TIME,<rtc_seconds>,<gnss_sync_unix>,<current_unix>,<sync_age>,<YYYY-MM-DD HH:MM:SS>
220+
$START,<count>,<start_systime>
221+
$E,<event_time>,<event_channel>
222+
$STOP,<count>,<tm>.<tm_s100>,<stop_systime>,<events_total>,<hist_0>,...,<hist_63>
223+
$ENV,<count>,<tm>.<tm_s100>,<tempC>,<humidity>
14224
```

0 commit comments

Comments
 (0)