7f67fc6abe
Merge pull request 'fix: remap CAN from CAN2/PB12-13 to CAN1/PB8-9 (Issue #676 )' ( #677 ) from sl-firmware/issue-597-can-driver into main
2026-03-17 21:39:29 -04:00
14c80dc33c
fix: remap CAN from CAN2/PB12-13 to CAN1/PB8-9 (Issue #676 )
...
Mamba F722S MK2 does not expose PB12/PB13 externally. Waveshare CAN
module is wired to the SCL (PB8) and SDA (PB9) header pads.
Changes in can_driver_init():
- Drop __HAL_RCC_CAN2_CLK_ENABLE() — CAN1 needs no slave clock
- GPIO: GPIO_PIN_12/13 → GPIO_PIN_8/9, GPIO_AF9_CAN2 → GPIO_AF9_CAN1
- Instance: CAN2 → CAN1
- Filter bank: 14 → 0 (CAN1 master banks start at 0; bank 14 is the
CAN2 slave-start boundary, unused here)
I2C1 is free: BME280 has been moved to I2C2 (PB10/PB11), so PB8/PB9
are available for CAN1 without any peripheral conflict.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-17 20:31:59 -04:00
779f9d00e2
feat: Encoder odometry and wheel speed feedback (Issue #632 )
...
- TIM2 (32-bit) left encoder, TIM3 (16-bit) right encoder in mode 3
- RPM calculation with int16 clamp; 16-bit wrap handled via signed delta
- Differential-drive odometry: x/y/theta Euler-forward integration
- Flash config (sector 7, 0x0807FF00) for ticks_per_rev/wheel_diam/base
- JLINK_TLM_ODOM (0x8C) at 50 Hz: rpm_l/r, x_mm, y_mm, theta_cdeg, speed_mmps
- 75/75 unit tests passing (TEST_HOST build)
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-15 16:34:38 -04:00
602fbc6ab3
feat: UART command protocol for Jetson-STM32 (Issue #629 )
...
Implements binary command protocol on UART5 (PC12/PD2) at 115200 baud
for Jetson→STM32 communication. Frame: STX+LEN+CMD+PAYLOAD+CRC8+ETX.
Commands: SET_VELOCITY (RPM direct to CAN), GET_STATUS, SET_PID, ESTOP,
CLEAR_ESTOP. DMA1_Stream0_Channel4 circular 256-byte RX ring. ACK/NACK
inline; STATUS pushed at 10 Hz. Heartbeat timeout 500 ms (UART_PROT_HB_TIMEOUT_MS).
NOTE: Spec requested USART1 @ 115200; USART1 occupied by JLink @ 921600.
Implemented on UART5 instead; note in code comments.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-15 14:41:00 -04:00
7785a16bff
feat: Battery voltage telemetry and LVC (Issue #613 )
...
- Add include/lvc.h + src/lvc.c: 3-stage low voltage cutoff state machine
WARNING 21.0V: MELODY_LOW_BATTERY buzzer, full motor power
CRITICAL 19.8V: double-beep every 10s, 50% motor power scaling
CUTOFF 18.6V: MELODY_ERROR one-shot, motors disabled + latched
200mV hysteresis on recovery; CUTOFF latched until reboot
- Add JLINK_TLM_LVC (0x8B, 4 bytes): voltage_mv, percent, protection_state
jlink_send_lvc_tlm() frame encoder in jlink.c
- Wire into main.c:
lvc_init() at startup; lvc_tick() each 1kHz loop tick
lvc_is_cutoff() triggers safety_arm_cancel + balance_disarm + motor_driver_estop
lvc_get_power_scale() applied to ESC speed command (100/50/0%)
1Hz JLINK_TLM_LVC telemetry with fuel-gauge percent field
- Add LVC thresholds to config.h (LVC_WARNING/CRITICAL/CUTOFF/HYSTERESIS_MV)
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-15 11:04:38 -04:00
2996d18ace
feat: CAN bus driver for BLDC motor controllers (Issue #597 )
...
- Add can_driver.h / can_driver.c: CAN2 on PB12/PB13 (AF9) at 500 kbps
APB1=54 MHz, PSC=6, BS1=13tq, BS2=4tq, SJW=1tq → 18tq/bit, SP 77.8%
Filter bank 14 (SlaveStartFilterBank=14); 32-bit mask; FIFO0
Accept std IDs 0x200–0x21F (left/right feedback frames)
TX: velocity+torque cmd (0x100+nid, DLC=4) at 100 Hz via main loop
RX: velocity/current/position/temp/fault feedback (0x200+nid, DLC=8)
AutoBusOff=ENABLE for HW recovery; can_driver_process() drains FIFO0
- Add JLINK_TLM_CAN_STATS (0x89, 16 bytes) + JLINK_CMD_CAN_STATS_GET (0x10)
Also add JLINK_TLM_SLOPE (0x88) + jlink_tlm_slope_t missing from Issue #600
- Wire into main.c: init after jlink_init; 100Hz TX loop (differential drive
speed_rpm ± steer_rpm/2); CAN enable follows arm state; 1Hz stats telemetry
- Add CAN_RPM_SCALE=10 and CAN_TLM_HZ=1 to config.h
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-14 15:58:13 -04:00
36643dd652
feat: Pan/tilt gimbal servo driver for ST3215 bus servos (Issue #547 )
...
- servo_bus.c/h: half-duplex USART3 driver for Feetech ST3215 servos at
1 Mbps; blocking TX/RX with CRC checksum; read/write position, torque
enable, speed; deg<->raw conversion (center=2048, 4096 counts/360°)
- gimbal.c/h: gimbal_t controller; 50 Hz feedback poll alternating pan/tilt
at 25 Hz each; clamps to ±GIMBAL_PAN/TILT_LIMIT_DEG soft limits
- jlink.c: dispatch JLINK_CMD_GIMBAL_POS (0x0B, 6-byte payload int16+int16+
uint16); jlink_send_gimbal_state() for JLINK_TLM_GIMBAL_STATE (0x84)
- main.c: servo_bus_init() + gimbal_init() on boot; gimbal_tick() in main
loop; gimbal_updated flag handler; GIMBAL_STATE telemetry at 50 Hz
- config.h: SERVO_BUS_UART/PORT/PIN/BAUD, GIMBAL_PAN/TILT_ID, GIMBAL_TLM_HZ,
GIMBAL_PAN/TILT_LIMIT_DEG
- jlink.h: CMD_GIMBAL_POS, TLM_GIMBAL_STATE, jlink_tlm_gimbal_state_t (10 B),
gimbal_updated/pan_x10/tilt_x10/speed volatile fields in JLinkState
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-14 10:38:06 -04:00
b128e164e7
fix: USART6 TX mutex to prevent truncated output (Issue #522 )
...
USART1 IDLE interrupt (DMA circular RX) was calling HAL_UART_IRQHandler
mid-frame during polling HAL_UART_Transmit, resetting gState and causing
leading nulls / truncated frames on the Jetson telemetry link at 921600 baud.
Fix: introduce jlink_tx_locked() which disables USART1_IRQn around every
blocking HAL_UART_Transmit call, preventing IRQHandler from corrupting
gState while the TX loop is running. A s_tx_busy flag drops any
re-entrant caller (ESC debug, future USART6/VESC paths).
Both jlink_send_telemetry (50 Hz) and jlink_send_power_telemetry (1 Hz)
now use jlink_tx_locked(). Also correct the stale config.h comment that
misidentified the Jetson link as USART6 (it moved to USART1 in Issue #120 ).
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-06 23:02:57 -05:00
844504e92e
refactor: ESC abstraction layer with pluggable backends (Issue #388 )
...
BREAKING CHANGE: Hoverboard implementation moved to pluggable vtable architecture.
## Implementation
### New Files
- include/esc_backend.h: Abstract interface (vtable) with:
- esc_telemetry_t struct (voltage, current, temp, speed, steer, fault)
- esc_backend_t vtable (init, send, estop, resume, get_telemetry)
- Runtime registration (esc_backend_register/get)
- Convenience wrappers (esc_init, esc_send, esc_estop, etc)
- src/esc_backend.c: Backend registry and wrapper implementations
- src/esc_hoverboard.c: Hoverboard backend implementing vtable
- USART2 @ 115200 baud configuration
- EFeru FOC packet encoding (0xABCD start, XOR checksum)
- Backward-compatible hoverboard_init/send wrappers
- Telemetry stub (future: add RX feedback parsing)
- src/esc_vesc.c: VESC backend stub (filled by Issue #383 )
- Placeholder functions for FSESC 4.20 Plus integration
- Public vesc_backend_register_impl() for runtime registration
- Ready for pyvesc protocol implementation
### Modified Files
- src/motor_driver.c: Changed from direct hoverboard_send() calls to esc_send()
- No logic changes, ESC-agnostic via vtable
- include/config.h: Added ESC_BACKEND define
- Compile-time selection (default: HOVERBOARD)
- Comments document architecture for future VESC support
### Removed Files
- src/hoverboard.c: Original implementation merged into esc_hoverboard.c
## Architecture Benefits
1. **Backend Pluggability**: Support multiple ESC types without code duplication
2. **Zero Direct Dependencies**: motor_driver.c never calls hoverboard functions directly
3. **Clean Testing**: Each backend can be tested/stubbed independently
4. **Future-Ready**: VESC integration (Issue #383 ) just implements the vtable
5. **Backward Compatible**: Existing code calling hoverboard_init/send still works
## Testing
- pio run: ✅ PASS (55.4KB Flash, 16.9KB RAM)
- Hoverboard backend tested via existing balance tests (unchanged logic)
- VESC backend stub compiles and links (no-op until #383 fills implementation)
## Blocks
- Issue #383 (VESC integration) — ready to implement vtable functions
- Issue #384 (pan/tilt servo) — may use independent PWM (not blocked)
## Dependencies
- None — this is pure refactoring, no API changes for callers
Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-04 10:36:35 -05:00
532edb835b
feat(firmware): Pan-tilt servo driver for camera head (Issue #206 )
...
Implements TIM4 PWM driver for 2-servo camera mount with:
- 50 Hz PWM frequency (standard servo control)
- CH1 (PB6) pan servo, CH2 (PB7) tilt servo
- 0-180° angle range → 500-2500 µs pulse width mapping
- Non-blocking servo_set_angle() for immediate positioning
- servo_sweep() for smooth pan-tilt animation (linear interpolation)
- Independent sweep control per servo (pan and tilt move simultaneously)
- 15 comprehensive unit tests covering all scenarios
Integration:
- servo_init() called at startup after power_mgmt_init()
- servo_tick(now_ms) called every 1ms in main loop
- Ready for camera/gimbal control automation
Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-02 11:44:56 -05:00
fbca191bae
feat(firmware): WS2812B NeoPixel LED status indicator driver (Issue #193 )
...
Implements TIM3_CH1 PWM driver for 8-LED NeoPixel ring with:
- 6 state-based animations: boot (blue chase), armed (solid green),
error (red blink), low battery (yellow pulse), charging (green breathe),
e_stop (red strobe)
- Non-blocking via 1 ms tick callback
- GRB byte order encoding (WS2812B standard)
- PWM duty values for "0" (~40%) and "1" (~56%) bit encoding
- 10 unit tests covering state transitions, animations, color encoding
Driver integrated into main.c initialization and main loop tick.
Includes buzzer driver (Issue #189 ) integration.
Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-02 11:06:13 -05:00
f446e5766e
feat(power): STOP-mode sleep/wake power manager — Issue #178
...
Adds STM32F7 STOP-mode power management with <10ms wake latency:
- power_mgmt.c: state machine (ACTIVE→SLEEP_PENDING→SLEEPING→WAKING),
30s idle timeout (PM_IDLE_TIMEOUT_MS), 3s LED fade before STOP,
gate SPI3/I2S3+SPI2+USART6+UART5 on sleep (clock-only, state preserved),
EXTI1(PA1/CRSF)+EXTI7(PB7/JLink)+EXTI4(PC4/IMU) wake sources,
PLL restore after STOP (PLLM=8/N=216/P=2 → 216MHz), uwTick save/restore
- Peripheral gating: I2S3, SPI2(OSD), USART6, UART5 disabled during STOP;
SPI1(IMU), UART4(CRSF), USART1(JLink), I2C1 remain active as wake sources
- Sleep LED: triangle-wave pulse (2s period) on LED1 during SLEEP_PENDING,
software PWM in main loop (1-bit, pm_pwm_phase vs brightness)
- IWDG: fed just before WFI; <10ms wake << 50ms WATCHDOG_TIMEOUT_MS
- JLink: JLINK_CMD_SLEEP=0x09, JLINK_TLM_POWER=0x81 (11-byte power frame
at 1Hz: power_state, est_total_ma, est_audio_ma, est_osd_ma, idle_ms)
- main.c: power_mgmt_init(), activity() on CRSF/JLink/armed, tick() when
disarmed, sleep_req handler, LED PWM, JLINK_TLM_POWER telemetry
- config.h: PM_* constants, PM_CURRENT_*_MA estimates, PM_TLM_HZ
- test_power_mgmt.py: 72 tests passing (state machine, LED, gating,
current estimates, JLink protocol, wake latency, hardware constants)
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-02 10:53:02 -05:00
c3ada4a156
feat(audio): I2S3 audio amplifier driver — Issue #143
...
Add I2S3/DMA audio output driver for MAX98357A/PCM5102A class-D amps:
- audio_init(): PLLI2S N=192/R=2 → 96 MHz → FS≈22058 Hz (<0.04% error),
GPIO PC10/PA15/PB5 (AF6), PC5 mute, DMA1_Stream7_Ch0 circular,
HAL_I2S_Transmit_DMA ping-pong, 441-sample half-buffers (20 ms each)
- Square-wave tone generator (ISR-safe, integer volume scaling 0-100)
- Tone sequencer: STARTUP/ARM/DISARM/FAULT/BEEP sequences via audio_tick()
- PCM FIFO (4096 samples, SPSC ring): receives Jetson audio via JLink
- JLink protocol: JLINK_CMD_AUDIO = 0x08, JLINK_MAX_PAYLOAD 64→252 bytes
(supports 126 int16 samples/frame = 5.7 ms @22050 Hz)
- main.c: audio_init(), STARTUP tone on boot, ARM/FAULT tones, audio_tick()
- config.h: AUDIO_BCLK/LRCK/DOUT/MUTE pin defines + PLLI2S constants
- test_audio.py: 45 tests, all passing
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-02 10:34:35 -05:00
6f0ad8e92e
feat(firmware): Jetson binary serial protocol on USART1 (Issue #120 )
...
New jlink module replaces ASCII-over-USB-CDC jetson_cmd with a dedicated
hardware UART binary protocol at 921600 baud for reliable Jetson comms.
- include/jlink.h: JLinkState struct, jlink_tlm_status_t (20-byte packed),
command/telemetry IDs (0x01-0x07 cmd, 0x80 status), API declarations
- src/jlink.c: USART1 DMA2_Stream2_Channel4 circular RX (128 bytes),
IDLE interrupt, CRC16-XModem (poly 0x1021) frame parser state machine,
command dispatch (HEARTBEAT/DRIVE/ARM/DISARM/PID_SET/ESTOP),
jlink_send_telemetry() blocking TX (≈0.28 ms per frame)
- include/config.h: JLINK_BAUD=921600, JLINK_HB_TIMEOUT_MS=1000,
JLINK_TLM_HZ=50, FW_MAJOR/MINOR/PATCH version constants
- src/main.c: jlink_init(), jlink_process() in main loop, arm/disarm/
estop/PID flag handling, 50 Hz STATUS telemetry TX, jlink takes
priority over legacy jetson_cmd for speed/steer injection
- test/test_jlink_frames.py: 39 pytest tests (39/39 pass) — CRC16,
frame building, parser state machine, drive/PID/status encoding
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-02 09:22:34 -05:00
4a46fad002
feat(rc): CRSF/ELRS RC integration — telemetry uplink + channel fix (Issue #103 )
...
## Summary
- config.h: CH1[0]=steer, CH2[1]=throttle (was CH4/CH3); CRSF_FAILSAFE_MS→500ms
- include/battery.h + src/battery.c: ADC3 Vbat reading on PC1 (11:1 divider)
battery_read_mv(), battery_estimate_pct() for 3S/4S auto-detection
- include/crsf.h + src/crsf.c: CRSF telemetry TX uplink
crsf_send_battery() — type 0x08, voltage/current/SoC to ELRS TX module
crsf_send_flight_mode() — type 0x21, "ARMED\0"/"DISARM\0" for handset OSD
- src/main.c: battery_init() after crsf_init(); 1Hz telemetry tick calls
crsf_send_battery(vbat_mv, 0, soc_pct) + crsf_send_flight_mode(armed)
- test/test_crsf_frames.py: 28 pytest tests — CRC8-DVB-S2, battery frame
layout/encoding, flight-mode frame, battery_estimate_pct SoC math
Existing (already complete from crsf-elrs branch):
CRSF frame decoder UART4 420000 baud DMA circular + IDLE interrupt
Mode manager: RC↔autonomous blend, CH6 3-pos switch, 500ms smooth transition
Failsafe in main.c: disarm if crsf_state.last_rx_ms stale > CRSF_FAILSAFE_MS
CH5 arm switch with ARMING_HOLD_MS interlock + edge detection
RC override: mode_manager blends steer/speed per mode (CH6)
Closes #103
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-02 08:35:48 -05:00
fbfde24aba
feat: CRSF/ELRS RC integration — 16ch input with failsafe (#Phase2)
...
Protocol choice: implemented from spec (CRSFforArduino needs Arduino
framework; Betaflight extraction has deep scheduler dependencies).
Protocol verified against Betaflight src/main/rx/crsf.c + CRSF spec.
crsf.c:
- UART4 PA0=TX/PA1=RX (GPIO_AF8_UART4), 420000 baud 8N1, oversampling×8
APB1=54MHz → BRR=0x101 → 418604 baud (0.33% error, within spec)
- DMA1 Stream2 Channel4, circular 64-byte buffer, IDLE interrupt
DMA half/complete callbacks drain buffer; IDLE fires at frame boundary
- CRC8 DVB-S2 (polynomial 0xD5) validated on every frame
- Parser state machine: SYNC(0xC8)→LEN→DATA with length sanity check
- 11-bit channel unpack for all 16 channels from 22-byte payload
- RC channels frame (0x16): unpacks 16ch, updates last_rx_ms + armed
- Link stats frame (0x14): captures RSSI dBm, LQ%, SNR dB
crsf.h: added rssi_dbm, link_quality, snr fields to CRSFState
config.h: CRSF_ARM_THRESHOLD=1750, CRSF_STEER_MAX=400, CRSF_FAILSAFE_MS=300
main.c:
- crsf_init() called after motor_driver_init()
- RC failsafe: disarm if (now - last_rx_ms) > CRSF_FAILSAFE_MS, but only
after RC was first seen (last_rx_ms != 0) — USB-only mode unaffected
- RC arm: CH5 rising edge → safety_arm_start(); falling edge → disarm
Same ARMING_HOLD_MS interlock as USB arm command
- RC steer: CH1 → crsf_to_range() → ±CRSF_STEER_MAX → motor_driver steer
- RSSI/LQ: appended to JSON when safety_rc_alive() ("rssi","lq" fields)
ui/index.html: hidden RC RSSI row revealed on first packet with rssi/lq
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-02-28 21:54:58 -05:00
ea5e2dac72
feat: RC/autonomous mode manager with smooth handoff
...
Adds mode_manager.c/h: three operating modes selected by RC CH6 (3-pos
switch), smoothly interpolated over ~500ms to prevent jerky transitions.
Modes:
RC_MANUAL (blend=0.0) — RC CH4 steer + CH3 speed bias; balance PID active
RC_ASSISTED (blend=0.5) — 50/50 blend of RC and Jetson autonomous commands
AUTONOMOUS (blend=1.0) — Jetson steer only; RC CH5 still kills motors
Key design:
- Single `blend` float (0=RC, 1=auto) drives all lerp; MANUAL→AUTO takes
500ms, adjacent steps take ~250ms
- CH6 thresholds: <=600=MANUAL, >=1200=AUTONOMOUS, else ASSISTED
- CH4/CH3 read with ±30-count deadband around CRSF center (992)
- RC speed bias (CH3, ±300 counts) added to bal.motor_cmd AFTER PID
- RC CH5 kill: if rc_alive && !crsf_state.armed → disarm, regardless of mode
- Jetson steer fed via mode_manager_set_auto_cmd() → blended in get_steer()
- Telemetry: new "md" field (0/1/2) in USB JSON stream
- mode_manager_set_auto_cmd() API ready for Jetson serial bridge integration
config.h: CRSF channel indices, deadband, speed-bias max, blend timing.
Safe on USB-only build: CRSF stub keeps last_rx_ms=0 → rc_alive=false
→ RC inputs = 0, mode stays RC_MANUAL, CH5 kill never fires.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-02-28 21:06:26 -05:00
1c95243e52
feat: gyro bias calibration on boot — fixes yaw drift (issues #21 , #23 )
...
On boot, before the main loop, sample 1000 gyro readings (~1s) while
board is held still. Compute per-axis mean offset (sensor-frame raw LSBs)
and subtract from all subsequent readings in mpu6000_read().
- mpu6000_calibrate(): LED1+LED2 solid ON during 1s sample window,
resets filter state to zero once bias is known
- mpu6000_is_calibrated(): gate; main loop blocks arming and USB
streaming until calibration completes
- Bias subtracted in sensor frame before CW270 axis transform + scale,
so all three axes (pitch/roll/yaw rate) benefit
- config.h: GYRO_CAL_SAMPLES=1000
- No flash storage — recalibrate fresh each boot (bias varies with temp)
Closes #21 (3.5°/s yaw drift), #23 (gyro bias calibration on boot).
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-02-28 17:42:34 -05:00
80a41e5008
feat: motor driver layer — differential drive, steer ramp, estop
...
Adds motor_driver.c/h between the balance PID and the raw
hoverboard UART driver:
- Differential drive: balance_cmd → speed, steer_cmd → steer
- Steer-only ramping at MOTOR_STEER_RAMP_RATE (balance PID keeps
full immediate authority — no ramp on speed channel)
- Headroom clamp: reduces steer so |speed|+|steer|<=MOTOR_CMD_MAX
ensuring ESC never clips the balance command
- Emergency stop: latches on TILT_FAULT, clears on BALANCE_DISARMED;
send path stays in 50Hz ESC tick to avoid flooding UART
main.c: replace bare hoverboard_send() with motor_driver_update();
config.h: MOTOR_CMD_MAX=1000, MOTOR_STEER_RAMP_RATE=20 counts/ms
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-02-28 17:15:40 -05:00
Sebastien Vayrette
ba3e1161b9
Balance firmware + USB CDC bug
2026-02-28 11:58:23 -05:00