72 Commits

Author SHA1 Message Date
5e82878083 feat: bxCAN integration for VESC motor control and Orin comms (Issue #674)
- can_driver: add filter bank 15 (all ext IDs → FIFO1) and widen bank 14
  to accept all standard IDs; add can_driver_send_ext/std and ext/std
  frame callbacks (can_driver_set_ext_cb / can_driver_set_std_cb)
- vesc_can: VESC 29-bit extended CAN protocol driver — send RPM to IDs 56
  and 68 (FSESC 6.7 Pro Mini Dual), parse STATUS/STATUS_4/STATUS_5
  big-endian payloads, alive timeout, JLINK_TLM_VESC_STATE at 1 Hz
- orin_can: Orin↔FC standard CAN protocol — HEARTBEAT/DRIVE/MODE/ESTOP
  commands in, FC_STATUS + FC_VESC broadcast at 10 Hz
- jlink: add JLINK_TLM_VESC_STATE (0x8E), jlink_tlm_vesc_state_t (22 bytes),
  jlink_send_vesc_state_tlm()
- main: wire vesc_can_init/orin_can_init; replace can_driver_send_cmd with
  vesc_can_send_rpm; inject Orin CAN speed/steer into balance PID; add
  Orin CAN estop/clear handling; add orin_can_broadcast at 10 Hz
- test: 56-test host-side suite for vesc_can; test/stubs/stm32f7xx_hal.h
  minimal HAL stub for all future host-side tests

Safety: balance PID runs independently on Mamba — if Orin CAN link drops
(orin_can_is_alive() == false) the robot continues balancing in-place.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-17 21:41:19 -04:00
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
ea5203b67d fix: bump arm pitch threshold 10°→20° (Issue #678)
Mamba is mounted at ~12° on the frame, causing all three arm-interlock
checks to block arming. Raise fabsf(bal.pitch_deg) < 10.0f to 20.0f
at lines 375, 512, 532 (JLink arm, RC arm rising-edge, CDC arm).

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-17 21:38:02 -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
1e69337ffd feat: Steering PID for differential drive (Issue #616)
Closed-loop yaw-rate controller that converts Jetson Twist.angular.z
to a differential wheel speed offset using IMU gyro Z as feedback.

- include/steering_pid.h + src/steering_pid.c: PID with anti-windup
  (integral clamped to ±200 counts) and rate limiter (10 counts/ms
  max output change) to protect balance PID from sudden steering steps.
  JLINK_TLM_STEERING (0x8A) telemetry at 10 Hz.
- include/mpu6000.h + src/mpu6000.c: expose yaw_rate (board_gz) in
  IMUData so callers have direct bias-corrected gyro Z feedback.
- include/jlink.h + src/jlink.c: add JLINK_TLM_STEERING (0x8A),
  jlink_tlm_steering_t (8 bytes), jlink_send_steering_tlm().
- test/test_steering_pid.c: 78 unit tests (host build with gcc),
  all passing.

Usage (main loop):
  steering_pid_set_target(&s, jlink_state.steer * STEER_OMEGA_SCALE);
  int16_t steer_out = steering_pid_update(&s, imu.yaw_rate, dt);
  motor_driver_update(&motor, balance_cmd, steer_out, now_ms);

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-15 10:11:05 -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
5f03e4cbef feat: Tilt compensation for slopes (Issue #600)
Adds a slow-adapting terrain slope estimator (IIR tau=5s) that decouples
the robot's balance offset from genuine ground incline.  The balance
controller subtracts the slope estimate from measured pitch so the PID
balances around the slope surface rather than absolute vertical.

- include/slope_estimator.h + src/slope_estimator.c: first-order IIR
  filter clamped to ±15°; JLINK_TLM_SLOPE (0x88) telemetry at 1 Hz
- include/jlink.h + src/jlink.c: add JLINK_TLM_SLOPE (0x88),
  jlink_tlm_slope_t (4 bytes), jlink_send_slope_tlm()
- include/balance.h + src/balance.c: integrate slope_estimator into
  balance_t; update, reset on tilt-fault and disarm
- test/test_slope_estimator.c: 35 unit tests, all passing

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-14 15:04:58 -04:00
8fbe7c0033 feat: STM32 watchdog and fault recovery handler (Issue #565)
- New src/fault_handler.c + include/fault_handler.h:
  - HardFault/MemManage/BusFault/UsageFault naked ISR stubs with
    Cortex-M7 stack-frame capture (R0-R3, LR, PC, xPSR, CFSR, HFSR,
    MMFAR, BFAR, SP) and NVIC_SystemReset()
  - .noinit SRAM capture ring survives soft reset; persisted to flash
    sector 7 (0x08060000, 8x64-byte slots) on subsequent boot
  - MPU Region 0 stack guard (32 B at __stack_end, no-access) ->
    MemManage fault detected as FAULT_STACK_OVF
  - Brownout detect via RCC_CSR_BORRSTF on boot -> FAULT_BROWNOUT
  - Watchdog reset detection delegates to existing watchdog.c
  - LED blink codes on LED2 (PC14, active-low) for 10 s post-recovery:
    HARDFAULT=3, WATCHDOG=2, BROWNOUT=1, STACK_OVF=4 fast blinks
  - fault_led_tick(), fault_log_read(), fault_log_get_count(),
    fault_get_last_type(), fault_log_clear(), FAULT_ASSERT() macro
- jlink.h: add JLINK_CMD_FAULT_LOG_GET (0x0F), JLINK_TLM_FAULT_LOG
  (0x86), jlink_tlm_fault_log_t (20 bytes), fault_log_req in JLinkState,
  jlink_send_fault_log() declaration
- jlink.c: dispatch JLINK_CMD_FAULT_LOG_GET; implement
  jlink_send_fault_log() (26-byte CRC16-XModem framed response)
- main.c: call fault_handler_init() first in main(); send fault log
  TLM on boot if prior fault recorded; fault_led_tick() in main loop;
  handle fault_log_req flag to respond to Jetson queries

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-14 13:37:14 -04:00
2b06161cb4 feat: Motor current monitoring and overload protection (Issue #584)
Adds ADC-based motor current sensing with configurable overload threshold,
soft PWM limiting, hard cutoff on sustained overload, and auto-recovery.

Changes:
- include/motor_current.h: MotorCurrentState enum (NORMAL/SOFT_LIMIT/COOLDOWN),
  thresholds (5A hard, 4A soft, 2s overload, 10s cooldown), full API
- src/motor_current.c: reads battery_adc_get_current_ma() each tick (reuses
  existing ADC3 IN13/PC3 DMA sampling); linear PWM scale in soft-limit zone
  (scale256 fixed-point); fault counter + one-tick fault_pending flag for
  main-loop fault log integration; telemetry at MOTOR_CURR_TLM_HZ (5 Hz)
- include/pid_flash.h: add pid_sched_entry_t (16 bytes), pid_sched_flash_t
  (128 bytes at 0x0807FF40), PID_SCHED_MAX_BANDS=6, pid_flash_load_schedule(),
  pid_flash_save_all() — fixes missing types needed by jlink.h (Issue #550)
- src/pid_flash.c: implement flash_write_words() helper, pid_flash_load_schedule(),
  pid_flash_save_all() — single sector-7 erase covers both schedule and PID records
- include/jlink.h: add JLINK_TLM_MOTOR_CURRENT (0x86), jlink_tlm_motor_current_t
  (8 bytes: current_ma, limit_pct, state, fault_count), jlink_send_motor_current_tlm()
- src/jlink.c: implement jlink_send_motor_current_tlm() (14-byte frame)

Motor overload state machine:
  MC_NORMAL     : current_ma < 4000 mA — full PWM authority
  MC_SOFT_LIMIT : 4000-5000 mA — linear reduction (0% at 4A → 100% at 5A)
  MC_COOLDOWN   : >5A sustained 2s → zero output for 10s then NORMAL

Main-loop integration:
  motor_current_tick(now_ms);
  if (motor_current_fault_pending()) fault_log_append(FAULT_MOTOR_OVERCURRENT);
  cmd = motor_current_apply_limit(balance_pid_output());
  motor_current_send_tlm(now_ms);

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-14 12:25:29 -04:00
8592361095 feat: PID gain scheduling for speed-dependent balance (Issue #550)
Implements a speed-dependent PID gain scheduler that interpolates Kp/Ki/Kd
across a configurable table of velocity breakpoints, replacing the fixed
single-gain PID used previously.

Changes:
- include/pid_flash.h: add pid_sched_entry_t (16-byte entry), pid_sched_flash_t
  (128-byte record at 0x0807FF40), pid_flash_load_schedule(), pid_flash_save_all()
  (atomic single-sector erase for both schedule and single-PID records)
- src/pid_flash.c: implement load_schedule and save_all; single erase covers
  both records at 0x0807FF40 (schedule) and 0x0807FFC0 (single PID)
- include/pid_schedule.h: API header -- init, get_gains, apply, set/get table,
  flash_save, active_band_idx, get_default_table
- src/pid_schedule.c: linear interpolation between sorted speed-band entries;
  integrator reset on band transition; default 3-band table (0/0.3/0.8 m/s)
- include/jlink.h: add SCHED_GET (0x0C), SCHED_SET (0x0D), SCHED_SAVE (0x0E)
  commands; TLM_SCHED (0x85); jlink_tlm_sched_t; JLinkSchedSetBuf;
  sched_get_req, sched_save_req fields in JLinkState; include pid_flash.h
- src/jlink.c: dispatch SCHED_GET/SET/SAVE; implement jlink_send_sched_telemetry,
  jlink_get_sched_set; add JLinkSchedSetBuf static buffer
- test/test_pid_schedule.c: 48 unit tests -- all passing (gcc host build)

Flash layout (sector 7):
  0x0807FF40  pid_sched_flash_t (128 bytes) -- schedule
  0x0807FFC0  pid_flash_t       ( 64 bytes) -- single PID (existing)

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-14 11:51:11 -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
59d164944d Merge origin/sl-controls/issue-533-battery-adc — resolve jlink conflicts
Keep both Issue #531 (PID_RESULT telemetry) and Issue #533 (BATTERY
telemetry) additions in include/jlink.h and src/jlink.c.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-07 10:10:26 -05:00
cc0ffd1999 feat: Battery voltage ADC driver with DMA sampling (Issue #533)
STM32F7 ADC driver for battery voltage/current monitoring using
DMA-based continuous sampling, IIR low-pass filter, voltage divider
calibration, and USART telemetry to Jetson. Integrates with power
management for low-battery sleep (Issue #467).

Implementation:
- include/battery_adc.h: New driver header with calibration struct and
  public API (init, tick, get_voltage_mv, get_current_ma, calibrate,
  publish, check_pm, is_low, is_critical)
- src/battery_adc.c: ADC3 continuous-scan DMA (DMA2_Stream0/Ch2), 4x
  hardware oversampling of both Vbat (PC1/IN11) and Ibat (PC3/IN13),
  IIR LPF (alpha=1/8, cutoff ~4 Hz at 100 Hz tick rate), calibration
  with ±500 mV offset clamp, 3S/4S auto-detection, 1 Hz USART publish
- include/jlink.h + src/jlink.c: Add JLINK_TLM_BATTERY (0x82) telemetry
  type and jlink_tlm_battery_t (10-byte packed struct), implement
  jlink_send_battery_telemetry() using CRC16-XModem framing
- include/power_mgmt.h + src/power_mgmt.c: Add
  power_mgmt_notify_battery() — triggers STOP-mode sleep when Vbat
  sustains critical level (Issue #467)
- test/test_battery_adc.c: 27 unit tests (27/27 passing): voltage
  conversion, calibration offset/scale, IIR LPF convergence, SoC
  estimation (3S/4S), low/critical flags, PM notification timing,
  calibration reset, publish rate-limiting

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-07 10:01:02 -05:00
19a30a1c4f feat: PID auto-tune for balance mode (Issue #531)
Implement Ziegler-Nichols relay feedback auto-tuning with flash persistence:

Firmware (STM32F722):
- pid_flash.c/h: erase+write Kp/Ki/Kd to flash sector 7 (0x0807FFC0),
  magic-validated; load on boot to restore saved tune
- jlink.h: add JLINK_CMD_PID_SAVE (0x0A) and JLINK_TLM_PID_RESULT (0x83)
  with jlink_tlm_pid_result_t struct and pid_save_req flag in JLinkState
- jlink.c: dispatch JLINK_CMD_PID_SAVE -> pid_save_req; add
  jlink_send_pid_result() to confirm flash write outcome over USART1
- main.c: load saved PID from flash after balance_init(); handle
  pid_save_req in main loop (disarmed-only, erase stalls CPU ~1s)

Jetson ROS2 (saltybot_pid_autotune):
- pid_autotune_node.py: add Ki to Ziegler-Nichols formula (ZN PID:
  Kp=0.6Ku, Ki=1.2Ku/Tu, Kd=0.075KuTu); add JLink serial client that
  sends JLINK_CMD_PID_SET + JLINK_CMD_PID_SAVE after tuning completes
- autotune_config.yaml: add jlink_serial_port and jlink_baud_rate params

Trigger: ros2 service call /saltybot/autotune_pid std_srvs/srv/Trigger

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-07 09:56:19 -05:00
e67783f313 Merge remote-tracking branch 'origin/sl-android/issue-521-esc-debug-cleanup' 2026-03-06 23:34:45 -05:00
5b7ee63d1e Merge remote-tracking branch 'origin/sl-controls/issue-522-usart6-truncation' 2026-03-06 23:34:45 -05:00
b0a5041261 fix: MPU6000 IMU calibration SPI/DCache issue (Issue #520)
Three bugs prevented mpu6000_is_calibrated() from returning true,
blocking arming and balance mode:

1. WHO_AM_I single-attempt: one SPI glitch returning 0x00 caused
   icm42688_init() to return -128, skipping mpu6000_calibrate()
   entirely. Fix: retry WHO_AM_I up to 3 times with 10ms gaps.

2. icm42688_read() rx[15] uninitialized: if HAL_SPI_TransmitReceive()
   failed, garbage stack data was accumulated as gyro bias. Fix: zero-
   init rx[15] so failed transfers produce zero data.

3. mpu6000_calibrate() raw uninitialized: UB if icm42688_read() is
   a no-op (imu_type mismatch). Fix: zero-init raw each iteration.

Also add SCB_InvalidateDCache_by_Addr() on SPI rx buffers in rreg()
and icm42688_read() for DCache coherency. Currently a no-op (DCache
is not enabled), but required if SCB_EnableDCache() is added — stack
buffers in SRAM2 are in the cacheable memory region on STM32F7.

Fix misleading DCache comment in icm42688.c (claimed DCache was
disabled by main.c; actually SCB_EnableDCache() is never called).

Build: 59904 bytes Flash (+512), 17100 bytes RAM — SUCCESS

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-06 23:14:49 -05:00
sl-android
d5246fe3a8 chore: Guard ESC debug output behind compile flag (Issue #521)
- esc_hoverboard.c: huart2 static in production; non-static only under
  #ifdef DEBUG_MOTOR_TEST (needed by R command in jetson_uart.c)
- esc_hoverboard.c: UART5 diagnostic in hoverboard_backend_init() and
  per-packet printf in hoverboard_backend_send() guarded by same flag
- esc_hoverboard.c: #include <stdio.h> also guarded (not needed in production)
- jetson_uart.c: R (baud sweep) and X (GPIO test) commands guarded by
  #ifdef DEBUG_MOTOR_TEST — not compiled into production firmware

Production build: no debug output, static huart2, no R/X commands.
Debug build: define DEBUG_MOTOR_TEST to re-enable all diagnostics.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-06 23:07:36 -05: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
Salty Bead
3bb4b71cea feat: motor bench test working — UART5 ESC + USART6 Jetson + W command
- Fix UART5 ESC: PC12=TX, PD2=RX @ 115200 baud (was USART2/38400)
- Add jetson_uart.c: USART6 command interface (A/D/E/Z/H/C/W/R/X/? commands)
- Add W command: persistent direct motor test (sets globals, main loop sends at 50Hz)
- Fix power_mgmt: keep UART5 clock active, PC7 EXTI wake source
- Fix main loop: direct_test_speed/steer override disarmed zero-send
- Add boot banner on USART6

Tested: Orin -> FC USART6 -> FC UART5 -> EFeru ESC -> both motors spin
2026-03-06 22:35:24 -05:00
48e9af60a9 feat: Remove ELRS arm requirement for autonomous operation (Issue #512)
Enable Jetson autonomous arming while keeping RC as optional override.

Key Changes:
=============

1. RC Kill Switch (CH5 OFF) → Emergency Stop (not disarm)
   - Motors cutoff immediately on kill switch
   - Robot remains armed (allows re-arm without re-initializing)
   - Maintains kill switch safety for emergency situations

2. RC Disarm Only on Explicit CH5 Falling Edge (while RC alive)
   - RC disconnect doesn't disarm Jetson-controlled missions
   - RC failsafe timer (500ms) still handles signal loss

3. Jetson Autonomous Arming (via CDC 'A' command)
   - Works independently of RC state
   - Requires: calibrated IMU, robot level (±10°), no estop active
   - Uses same 500ms arm-hold safety as RC

4. All Safety Preserved
   - Arming hold timer: 500ms
   - Tilt limit: ±10° level
   - IMU calibration required
   - Remote E-stop override
   - RC failsafe: 500ms signal loss = disarm
   - Jetson timeout: 500ms heartbeat = zero motors

Command Protocol (CDC):
   A = arm (Jetson)
   D = disarm (Jetson)
   E/Z = estop / clear estop
   H = heartbeat (keep-alive)
   C<spd>,<str> = drive command

Behavior Matrix:
   RC disconnected      → Jetson-armed stays armed, normal operation
   RC connected + armed → Both Jetson and RC can arm, blended control
   RC kill switch (CH5) → Emergency stop + can re-arm via Jetson 'A'
   RC signal lost       → Disarm after 500ms (failsafe)

See AUTONOMOUS_ARMING.md for complete protocol and testing checklist.

Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-06 11:46:03 -05:00
sl-android
49628bcc61 feat: Add Issue #507 - Face display animations on STM32 LCD
Implements expressive face animations with 5 core emotions (happy/sad/curious/angry/sleeping) and smooth transitions on small LCD displays.

Features:
- State machine with smooth 0.5s emotion transitions (ease-in-out cubic easing)
- Automatic idle blinking (4-6s intervals, 100-150ms duration per blink)
- UART command interface via USART3 @ 115200 (text-based protocol)
- 30Hz target refresh rate via systick integration
- Low-level LCD abstraction supporting monochrome and RGB565
- Rendering primitives: pixel, line (Bresenham), circle (midpoint), filled rect

Architecture:
- face_lcd.h/c: Hardware-agnostic framebuffer & display driver
- face_animation.h/c: Emotion state machine & parameterized face rendering
- face_uart.h/c: UART command parser (HAPPY/SAD/CURIOUS/ANGRY/SLEEP/NEUTRAL/BLINK/STATUS)
- Unit tests (14 test cases): emotion transitions, blinking, rendering, all emotions

Integration:
- main.c: Added includes, initialization (servo_init), systick tick, main loop processing
- Pending: LCD hardware initialization (SPI/I2C config, display controller setup)

Files: 9 new (headers, source, tests, docs), 1 modified (main.c)
Lines: ~1450 total (345 headers, 650 source, 350 tests, 900 docs)

Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-06 10:27:36 -05:00
170c64eec1 feat: Add watchdog reset detection and status reporting (Issue #300)
- Detect if MCU was reset by IWDG watchdog timeout at startup
- Log watchdog reset events to debug terminal (USB CDC)
- Store watchdog reset flag for status reporting to Jetson
- Watchdog timer configured with 2-second timeout in safety_init()
- Main loop calls safety_refresh() to kick the watchdog every iteration

The IWDG (Independent Watchdog) resets the MCU if the main loop
hangs and fails to call safety_refresh() within the timeout window.
This provides hardware-enforced detection of software failures.

Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-04 12:17:56 -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
d52e7af554 fix: Add missing bno055.h include to resolve implicit declaration warnings
Adds #include "bno055.h" to src/main.c to resolve implicit declaration
warnings for bno055_read(), bno055_calib_status(), and bno055_temperature().
Functions were properly implemented but header was missing from includes.

Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-04 08:45:51 -05:00
f4e71777ec fix: Resolve all compile and linker errors (Issue #337)
Fixed 7 compile errors across 6 files:

1. servo.c: Removed duplicate ServoState typedef, updated struct definition in header
2. watchdog.c: Fixed IWDG handle usage - moved to global scope for IRQHandler access
3. ultrasonic.c: Fixed timer handle type mismatches - use TIM_HandleTypeDef instead of TIM_TypeDef, replaced HAL_TIM_IC_Init_Compat with proper HAL functions
4. main.c: Replaced undefined functions - imu_calibrated() → mpu6000_is_calibrated(), crsf_is_active() → manual state check
5. ina219.c: Stubbed I2C functions pending HAL implementation

Build now passes with ZERO errors.
- RAM: 6.5% (16964 bytes / 262144)
- Flash: 10.6% (55368 bytes / 524288)

Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-03 19:00:12 -05:00
cfa8ee111d Merge pull request 'feat: Replace GNOME with Cage+Chromium kiosk (Issue #374)' (#377) from sl-webui/issue-374-cage-kiosk into main 2026-03-03 17:46:14 -05:00
410ace3540 feat: battery coulomb counter (Issue #325)
Add coulomb counter for accurate SoC estimation independent of load:

- New coulomb_counter module: integrate current over time to track Ah consumed
  * coulomb_counter_init(capacity_mah) initializes with battery capacity
  * coulomb_counter_accumulate(current_ma) integrates current at 100 Hz
  * coulomb_counter_get_soc_pct() returns SoC 0-100% (255 = invalid)
  * coulomb_counter_reset() for charge-complete reset

- Battery module integration:
  * battery_accumulate_coulombs() reads motor INA219 currents and accumulates
  * battery_get_soc_coulomb() returns coulomb-based SoC with fallback to voltage
  * Initialize coulomb counter at startup with DEFAULT_BATTERY_CAPACITY_MAH

- Telemetry updates:
  * JLink STATUS: use coulomb SoC if available, fallback to voltage-based
  * CRSF battery frame: now includes remaining capacity in mAh (from coulomb counter)
  * CRSF capacity field was always 0; now reflects actual remaining mAh

- Mainloop integration:
  * Call battery_accumulate_coulombs() every tick for continuous integration
  * INA219 motor currents + 200 mA subsystem baseline = total battery draw

Motor current sources (INA219 addresses 0x40/0x41) provide most power draw;
Jetson ROS2 battery_node already prioritizes coulomb-based soc_pct from STATUS frame.

Default capacity: 2200 mAh (typical lab 3S LiPo); configurable via firmware parameter.

Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-03 17:35:34 -05:00
5cec6779e5 feat: Integrate IWDG watchdog timer driver (Issue #300)
- Replace safety.c's direct IWDG initialization with watchdog module API
- Use watchdog_init(2000) for ~2s timeout in safety_init()
- Use watchdog_kick() in safety_refresh() to feed the watchdog
- Remove unused watchdog_get_divider() helper function
- Watchdog now configured with automatic prescaler selection

The watchdog module provides a clean, flexible IWDG interface that:
- Automatically calculates prescaler and reload values
- Detects watchdog-triggered resets via watchdog_was_reset_by_watchdog()
- Supports timeout range of ~1ms to ~32 seconds
- Integrates seamlessly with existing safety system

Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-03 17:29:59 -05:00
f12f0bdc2b feat(webui): motor current live graph (Issue #297)
Real-time motor current visualization with:
- Subscribes to /saltybot/motor_currents for dual-motor current data
- Rolling 60-second history window with automatic data culling
- Dual-axis line chart for left (cyan) and right (amber) motor amps
- Canvas-based rendering for performance
- Thermal warning threshold line (25A, configurable)
- Real-time statistics:
  * Current draw for left and right motors
  * Peak current tracking over 60-second window
  * Average current calculation
  * Thermal status indicator with warning badge
- Color-coded thermal alerts:
  * Red background when threshold exceeded
  * Warning indicator and message
- Grid overlay, axis labels, time labels, legend
- Takes absolute value of currents (handles reverse direction)

Integrated into TELEMETRY tab group as 'Motor Current' tab.

Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-02 21:09:17 -05:00
70e94dc100 feat: Add RGB status LED state machine (Issue #290)
Implements STM32F722 driver for WS2812 NeoPixel 8-LED ring with finite state machine.

Features:
- 8 operational states with animations:
  * BOOT: Blue pulse (0.5 Hz)
  * IDLE: Green breathe (0.5 Hz)
  * ARMED: Solid green
  * NAV: Cyan spin (1 Hz)
  * ERROR: Red flash (2 Hz)
  * LOW_BATT: Orange blink (1 Hz)
  * CHARGING: Green fill (1 Hz)
  * ESTOP: Red solid
- Non-blocking tick-based animation system
- State transitions via API
- PWM control on PB4 (TIM3_CH1) at 800 kHz
- Color interpolation for smooth effects

All 25 unit tests passing covering state transitions, animations, timing, and edge cases.

Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-02 20:49:26 -05:00
c348e093ef feat: Add cooling fan PWM speed controller (Issue #263)
Implements STM32F722 driver for brushless cooling fan on PA9 using TIM1_CH2 PWM.
Features:
- Temperature-based speed curve: off <40°C, 30% at 50°C, 100% at 70°C
- Smooth speed ramp transitions with configurable rate (default 0.05%/ms)
- Linear interpolation between curve points
- PWM duty cycle control (0-100%)
- State transitions and edge case handling

All 51 unit tests passing:
- Temperature curve verification (6 test zones)
- Speed boundaries and transitions
- Ramp timing and rate control
- PWM duty cycle calculation
- Temperature extremes and boundary conditions

Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-02 13:29:18 -05:00
8f51390e43 feat: Add piezo buzzer melody driver (Issue #253)
Implements STM32F7 non-blocking driver for piezo buzzer on PA8 using TIM1 PWM.
Plays predefined melodies and custom sequences with melody queue.

Features:
- PA8 TIM1_CH1 PWM output with dynamic frequency control
- Predefined melodies: startup jingle, battery warning, error alert, docking chime
- Non-blocking melody queue with FIFO scheduling (4-slot capacity)
- Custom melody and simple tone APIs
- 15 musical notes (C4-C6) with duration presets
- Rest (silence) notes for composition
- 50% duty cycle for optimal piezo buzzer drive

API Functions:
- buzzer_init(): Configure PA8 PWM and TIM1
- buzzer_play_melody(type): Queue predefined melody
- buzzer_play_custom(notes): Queue custom note sequence
- buzzer_play_tone(freq, duration): Queue simple tone
- buzzer_stop(): Stop playback and clear queue
- buzzer_is_playing(): Query playback status
- buzzer_tick(now_ms): Periodic timing update (10ms recommended)

Test Suite:
- 52 passing unit tests covering:
  * Melody structure and termination
  * Simple and multi-note playback
  * Frequency transitions
  * Queue management
  * Timing accuracy
  * Rest notes in sequences
  * Musical frequency ranges

Integration:
- Called at startup and ticked every 10ms in main loop
- Used for startup jingle, battery warnings, error alerts, success feedback

Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-02 12:51:42 -05:00
34a003d0b1 feat: Add HC-SR04 ultrasonic distance sensor driver (Issue #243)
Implements STM32F7 non-blocking driver for HC-SR04 ultrasonic ranger with TIM1 input capture.
Supports distance measurement via echo pulse width analysis.

Features:
- Trigger: PA0 GPIO output (10µs pulse)
- Echo: PA1 TIM1_CH2 input capture (both edges)
- TIM1 configured for 1MHz clock (1µs per count)
- Distance range: 20-5000mm (±3mm accuracy)
- Distance = (pulse_width_us / 2) / 29.1mm
- Non-blocking API with optional callback
- Timeout detection (30ms max echo wait)
- State machine: IDLE → TRIGGERED → MEASURING → COMPLETE/ERROR

API Functions:
- ultrasonic_init(): Configure GPIO and TIM1
- ultrasonic_trigger(): Start measurement
- ultrasonic_set_callback(): Register completion callback
- ultrasonic_get_state(): Query current state
- ultrasonic_get_result(): Retrieve measurement result
- ultrasonic_tick(): Periodic timeout handler

Test Suite:
- 26 passing unit tests
- Distance conversion accuracy (100mm-2000mm)
- State machine transitions
- Range validation (20-5000mm boundaries)
- Timeout detection
- Multiple sequential measurements

Integration:
- ultrasonic_init() called in main() startup after servo_init()
- Non-blocking operation suitable for autonomous navigation/obstacle avoidance

Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-02 12:22:09 -05:00
eceda99bb5 feat: Add INA219 dual motor current monitor driver (Issue #214)
Implements complete I2C1 driver for TI INA219 power monitoring IC supporting:
- Dual sensors on I2C1 (left motor @ 0x40, right motor @ 0x41)
- Auto-calibration for 5A max current, 0.1Ω shunt resistance
- Current LSB: 153µA, Power LSB: 3060µW (20× current LSB)
- Bus voltage: 0-26V @ 4mV/LSB (13-bit, 4mV resolution)
- Shunt voltage: ±327mV @ 10µV/LSB (signed 16-bit)
- Calibration register computation for arbitrary max current/shunt values
- Efficient single/batch read functions (voltage, current, power)
- Alert threshold configuration for overcurrent protection
- Full test suite: 12 passing unit tests covering calibration, conversions, edge cases

Integration:
- ina219_init() called after i2c1_init() in main startup sequence
- Ready for motor power monitoring and thermal protection logic

Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
2026-03-02 11:51:26 -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
566cfc8811 Merge pull request 'fix: IWDG reset during gyro recal — refresh at i=0 not i=39 (P0 #42)' (#172) from sl-firmware/gyro-recal-button into main 2026-03-02 10:34:20 -05:00
0f42e701e9 Merge pull request 'feat(firmware): OTA firmware update — USB DFU + dual-bank + CRC32 (Issue #124)' (#156) from sl-firmware/issue-124-ota into main 2026-03-02 10:08:40 -05:00
4beef8da03 feat(firmware): OTA DFU entry via JLink command and Python flash script (Issue #124)
- Add ota.h / ota.c: ota_enter_dfu() (armed guard, writes BKP15R, resets),
  ota_fw_crc32() using STM32F7 hardware CRC peripheral (CRC-32/MPEG-2, 512 KB)
- Add JLINK_CMD_DFU_ENTER (0x06) and dfu_req flag to jlink.h / jlink.c
- Handle dfu_req in main loop: calls ota_enter_dfu(is_armed) — no-op if armed
- Update usbd_cdc_if.c: move DFU magic from BKP0R to BKP15R (OTA_DFU_BKP_IDX)
  resolving BKP register conflict with BNO055 calibration (BKP0R–6R, PR #150)
- Add scripts/flash_firmware.py: CRC-32/MPEG-2 + ISO-HDLC verification,
  dfu-util flash, host-side backup/rollback, --trigger-dfu JLink serial path
- Add test/test_ota.py: 42 tests passing (CRC-32/MPEG-2, CRC-16/XMODEM,
  DFU_ENTER frame structure, BKP register safety, flash constants)

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-02 09:56:18 -05:00
87b45e1b97 feat(firmware): BNO055 NDOF IMU driver on I2C1 (Issue #135)
Auto-detected alongside MPU6000. Acts as balance primary when MPU6000
fails, or provides NDOF-fused yaw/pitch when both sensors are present.

- include/bno055.h: full API — bno055_init/read/is_ready/calib_status/
  temperature/save_offsets/restore_offsets
- src/bno055.c: I2C1 driver; probes 0x28/0x29, resets via SYS_TRIGGER,
  enters NDOF mode; 2-burst 12-byte reads (gyro+euler, LIA+gravity);
  Euler/gyro/accel scaling (÷16, ÷16, ÷100); auto-saves offsets to
  RTC backup regs BKP0R–BKP6R on first full cal; restores on boot
  (bno055_is_ready() returns true immediately); temperature updated 1Hz
- include/config.h: BNO055_BKP_MAGIC = 0xB055CA10
- src/main.c: bno055_init() in I2C probe block (before IWDG); imu_calibrated()
  macro dispatches mpu6000_is_calibrated() vs bno055_is_ready();
  BNO055 read deferred inside balance gate to avoid stalling main loop;
  USB JSON reports bno_cs (calib status) and bno_t (temperature)
- test/test_bno055_data.py: 43 pytest tests (43/43 pass) — calib status
  bit extraction, Euler/gyro/accel scaling, burst parsing, offset
  round-trip packing, temperature signed-byte encoding

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-02 09:40:18 -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
d41a9dfe10 feat(safety): remote e-stop over 4G MQTT (Issue #63)
STM32 firmware:
- safety.h/c: EstopSource enum, safety_remote_estop/clear/get/active()
  CDC 'E'=ESTOP_REMOTE, 'F'=ESTOP_CELLULAR_TIMEOUT, 'Z'=clear latch
- usbd_cdc_if: cdc_estop_request/cdc_estop_clear_request volatile flags
- status: status_update() +remote_estop param; both LEDs fast-blink 200ms
- main.c: immediate motor cutoff highest-priority; arming gated by
  !safety_remote_estop_active(); motor estop auto-clear gated; telemetry
  'es' field 0-4; status_update() updated to 5 args

Safety: IMMEDIATE motor cutoff, latched until explicit Z + DISARMED,
cannot re-arm via MQTT alone (requires RC arm hold). IWDG-safe.

Jetson bridge:
- remote_estop_node.py: paho-mqtt + pyserial, cellular watchdog 5s
- estop_params.yaml, remote_estop.launch.py
- setup.py / package.xml: register node + paho-mqtt dep
- docker-compose.yml: remote-estop service
- test_remote_estop.py: kill/clear/watchdog/latency unit tests

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-01 04:55:54 -05:00
6dc7aea32f feat: modern HUD dashboard + telemetry expansion (#43)
ui/index.html — full dashboard rewrite:
- 3-column layout: LEFT telemetry gauges, CENTER 3D SaltyBot, RIGHT comms
- LEFT: artificial horizon (canvas, pitch/roll/ladder/roll-arc), yaw compass
  tape, pitch/roll/yaw readouts, bidirectional motor bar, battery bar, BME280
  environment section (auto-shows on data), MAG heading row
- CENTER: Three.js SaltyBot model (PR#41) with ground plane + animated
  wheel rolling proportional to motor_cmd
- RIGHT: USB tx/rx packet counters, mode badge (MANUAL/ASSISTED/AUTO),
  CRSF RSSI/LQ, dual RC stick overlay canvases (CH1–4), Jetson active dot
- BOTTOM: KP/KI/KD/SP/MAX sliders with APPLY + QUERY, collapsible log console
- Style: Tailwind CSS CDN, dark cyberpunk theme, neon cyan + orange accents

src/main.c — telemetry JSON additions:
- buf: 256 → 320 bytes (headroom for new fields)
- ja: Jetson active flag (0/1) via jetson_cmd_is_active()
- txc: TX telemetry frame counter (uint32, main-loop local)
- rxc: RX CDC packet counter (cdc_rx_count from usbd_cdc_if)
- ch1–ch4: CRSF channels mapped to µs (1000–2000) via crsf_to_range(),
  appended alongside rssi/lq when RC is alive

lib/USB_CDC/src/usbd_cdc_if.c:
- cdc_rx_count: volatile uint32_t, incremented in CDC_Receive on every
  packet; extern'd in main.c for telemetry

Closes #43.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-02-28 22:41:02 -05:00