Skip to content

Commit 6188f9e

Browse files
c0ffee2codeclaude
andcommitted
Extract LeverMixer and reorganize telemetry into package (M3)
Move differential thrust mixing from inline main.py logic into a dedicated LeverMixer class. Move telemetry.py into telemetry/recorder.py to establish a telemetry package alongside the planned sdcard sink. Co-Authored-By: Claude Opus 4.6 <noreply@anthropic.com>
1 parent 2820097 commit 6188f9e

File tree

5 files changed

+37
-15
lines changed

5 files changed

+37
-15
lines changed

CLAUDE.md

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -14,14 +14,15 @@ Test bench for learning flight control systems, built around a Raspberry Pi Pico
1414

1515
## Development Approach
1616

17-
**Completed:** M1 — Single-axis PI(D) controller with AS5600 encoder, validated on hardware. Lever holds at 0° within ±3°. See `decision/ADR-001-pid-lever-stabilization.md`.
17+
**Completed:**
18+
- M1 — Single-axis PI(D) controller with AS5600 encoder, validated on hardware. Lever holds at 0° within ±3°. See `decision/ADR-001-pid-lever-stabilization.md`.
19+
- M3 — Mixer extraction (`LeverMixer` in `mixer.py`) + telemetry reorganization into `telemetry/` package.
1820

1921
**Current focus:** M2 — Switch PID input from AS5600 to BNO085 IMU. The IMU will be the primary and only control input (as on a real drone). AS5600 becomes telemetry-only ground truth for measuring IMU lag and angle error.
2022

2123
**Roadmap (see README.md for full details):**
2224
- M2: BNO085 as primary control input (depends on driver work)
2325
- M2a: Telemetry logging via Adalogger PiCowbell — RTC timestamps + SD card black box (see `decision/ADR-002-telemetry-logging.md`)
24-
- M3: Mixer abstraction (pure refactor)
2526
- M4: Cascaded PID — angle loop + rate loop using raw gyro (depends on M2, M2a, M3)
2627
- M5: Multi-axis control (depends on hardware evolution)
2728

@@ -39,6 +40,10 @@ Test bench for learning flight control systems, built around a Raspberry Pi Pico
3940

4041
```
4142
├── main.py # Entry point - upload to Pico, runs on boot
43+
├── mixer.py # LeverMixer — differential thrust for 2-motor lever
44+
├── telemetry/
45+
│ ├── recorder.py # TelemetryRecorder + PrintSink (CSV decimation & output)
46+
│ └── sdcard.py # SD card sink (planned)
4247
├── AS5600/ # Git submodule: github.com/c0ffee2code/AS5600
4348
│ └── driver/as5600.py
4449
├── BNO085/ # Git submodule: github.com/c0ffee2code/BNO085
@@ -56,6 +61,8 @@ Test bench for learning flight control systems, built around a Raspberry Pi Pico
5661

5762
**Deployment:** Upload the following files to Pico root (flat structure):
5863
- `main.py`
64+
- `mixer.py`
65+
- `telemetry/recorder.py` (deployed as `recorder.py`)
5966
- `AS5600/driver/as5600.py`
6067
- `BNO085/driver/bno08x.py` + `BNO085/driver/i2c.py`
6168
- `DShot/driver/dshot_pio.py` + `DShot/driver/motor_throttle_group.py`

README.md

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -34,9 +34,9 @@ Log timestamped data from both sensors + PID internals to SD card via Adalogger
3434

3535
**Depends on:** Adalogger hardware integration, motor pin reassignment (GPIO 4/5 → 6/7).
3636

37-
### M3: Mixer abstraction
37+
### M3: Mixer abstraction — DONE
3838

39-
Extract `base ± output` motor mapping into a configurable mixer module. Makes code drone-topology-agnostic — swap a mix table to support different frame types (2-motor lever, quadcopter X-frame, etc.).
39+
Extracted `base ± output` motor mapping into `LeverMixer` class (`mixer.py`). Makes code drone-topology-agnostic — swap a mix table to support different frame types (2-motor lever, quadcopter X-frame, etc.). Also reorganized telemetry into `telemetry/` package.
4040

4141
**Depends on:** M1 (pure code refactor, no hardware dependency).
4242

@@ -60,6 +60,10 @@ See [ADR-001, "Test Bench vs Real Drone" section](decision/ADR-001-pid-lever-sta
6060

6161
```
6262
├── main.py # Entry point — upload to Pico, runs on boot
63+
├── mixer.py # LeverMixer — differential thrust for 2-motor lever
64+
├── telemetry/ # Telemetry recording and output sinks
65+
│ ├── recorder.py # TelemetryRecorder + PrintSink
66+
│ └── sdcard.py # SD card sink (planned)
6367
├── AS5600/ # Git submodule: github.com/c0ffee2code/AS5600
6468
├── BNO085/ # Git submodule: github.com/c0ffee2code/BNO085
6569
├── DShot/ # Git submodule: github.com/c0ffee2code/DShot
@@ -77,6 +81,8 @@ git clone --recurse-submodules <repo-url>
7781

7882
Upload to Pico root (flat structure):
7983
- `main.py`
84+
- `mixer.py`
85+
- `telemetry/recorder.py` (as `recorder.py`)
8086
- `AS5600/driver/as5600.py`
8187
- `BNO085/driver/bno08x.py` + `i2c.py`
8288
- `DShot/driver/dshot_pio.py` + `motor_throttle_group.py`

main.py

Lines changed: 4 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,8 @@
88
from display_pack import (draw_disarmed, draw_arming, draw_ready,
99
draw_stabilizing, draw_error)
1010
from pid import PID
11-
from telemetry import TelemetryRecorder
11+
from recorder import TelemetryRecorder
12+
from mixer import LeverMixer
1213

1314
# =====================================================
1415
# Hardware
@@ -45,14 +46,6 @@
4546
TELEMETRY_SAMPLE_EVERY = const(10)
4647

4748

48-
def clamp(value, lo, hi):
49-
if value < lo:
50-
return lo
51-
if value > hi:
52-
return hi
53-
return value
54-
55-
5649
def buttons_by_held():
5750
"""Return True if B+Y are both pressed (active low)."""
5851
return not btn_B.value() and not btn_Y.value()
@@ -63,6 +56,7 @@ def buttons_by_held():
6356
# =====================================================
6457
def main():
6558
pid = PID(kp=5.0, ki=0.5, kd=0.0, integral_limit=200.0)
59+
mixer = LeverMixer(BASE_THROTTLE, THROTTLE_MIN, THROTTLE_MAX)
6660
telemetry = TelemetryRecorder(TELEMETRY_SAMPLE_EVERY)
6761
motors = MotorThrottleGroup([MOTOR1_PIN, MOTOR2_PIN], DSHOT_SPEEDS.DSHOT600)
6862

@@ -112,8 +106,7 @@ def main():
112106
# PID — target is 0°, error = angle (sign verified on hardware)
113107
output = pid.compute(angle, dt)
114108

115-
m1 = clamp(int(BASE_THROTTLE + output), THROTTLE_MIN, THROTTLE_MAX)
116-
m2 = clamp(int(BASE_THROTTLE - output), THROTTLE_MIN, THROTTLE_MAX)
109+
m1, m2 = mixer.compute(output)
117110

118111
motors.setThrottle(0, m1)
119112
motors.setThrottle(1, m2)

mixer.py

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
class LeverMixer:
2+
"""Differential thrust mixer for a 2-motor lever."""
3+
4+
def __init__(self, base, throttle_min, throttle_max):
5+
self.base = base
6+
self.throttle_min = throttle_min
7+
self.throttle_max = throttle_max
8+
9+
def compute(self, pid_output):
10+
"""Return (m1, m2) throttle values, clamped to limits."""
11+
m1 = self.base + int(pid_output)
12+
m2 = self.base - int(pid_output)
13+
# clamp
14+
m1 = max(self.throttle_min, min(self.throttle_max, m1))
15+
m2 = max(self.throttle_min, min(self.throttle_max, m2))
16+
return m1, m2
File renamed without changes.

0 commit comments

Comments
 (0)