sl-firmware fa75c442a7 feat: remove all STM32/Mamba/BlackPill references — ESP32-S3 only
Archive STM32 firmware to legacy/stm32/:
- src/, include/, lib/USB_CDC/, platformio.ini, test stubs, flash_firmware.py
- test/test_battery_adc.c, test_hw_button.c, test_pid_schedule.c, test_vesc_can.c, test_can_watchdog.c
- USB_CDC_BUG.md

Rename: stm32_protocol → esp32_protocol, mamba_protocol → balance_protocol,
  stm32_cmd_node → esp32_cmd_node, stm32_cmd_params → esp32_cmd_params,
  stm32_cmd.launch.py → esp32_cmd.launch.py,
  test_stm32_protocol → test_esp32_protocol, test_stm32_cmd_node → test_esp32_cmd_node

Content cleanup across all files:
- Mamba F722S → ESP32-S3 BALANCE
- BlackPill → ESP32-S3 IO
- STM32F722/F7xx → ESP32-S3
- stm32Mode/Version/Port → esp32Mode/Version/Port
- STM32 State/Mode labels → ESP32 State/Mode
- Jetson Nano → Jetson Orin Nano Super
- /dev/stm32 → /dev/esp32
- stm32_bridge → esp32_bridge
- STM32 HAL → ESP-IDF

docs/SALTYLAB.md:
- Update "Drone FC Details" to describe ESP32-S3 BALANCE board (Waveshare ESP32-S3 Touch LCD 1.28)
- Replace verbose "Self-Balancing Control" STM32 section with brief note pointing to SAUL-TEE-SYSTEM-REFERENCE.md

TEAM.md: Update Embedded Firmware Engineer role to ESP32-S3 / ESP-IDF

No new functionality — cleanup only.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-04-04 09:00:38 -04:00

144 lines
5.4 KiB
C
Raw Blame History

This file contains ambiguous Unicode characters

This file contains Unicode characters that might be confused with other characters. If you think that this is intentional, you can safely ignore this warning. Use the Escape button to reveal them.

/*
* battery_adc.h — DMA-based battery voltage/current ADC driver (Issue #533)
*
* Hardware:
* ADC3 channel IN11 (PC1) — Vbat through 10kΩ/1kΩ divider (11:1 ratio)
* ADC3 channel IN13 (PC3) — Ibat via shunt amplifier (ADC_IBAT_SCALE=115)
* DMA2 Stream0 Channel2 — ADC3 → memory circular (8-word buffer)
* USART1 (jlink) — telemetry to Jetson via JLINK_TLM_BATTERY (0x82)
*
* HOW IT WORKS:
* 1. ADC3 runs in continuous scan mode, alternating IN11 (Vbat) and IN13 (Ibat)
* at APB2/8 clock (≈ 13.5 MHz ADC clock on STM32F7 @ 216 MHz).
* 480-cycle sampling per channel → ~35 µs per scan pair, ~28 kHz scan rate.
*
* 2. DMA2_Stream0 (circular) fills an 8-word buffer: 4 Vbat samples followed
* by 4 Ibat samples per DMA half-complete cycle. Interleaved layout:
* [vbat0, ibat0, vbat1, ibat1, vbat2, ibat2, vbat3, ibat3]
*
* 3. battery_adc_tick() (call from main loop, 10100 Hz) averages the 4 Vbat
* and 4 Ibat raw values (4× hardware oversampling), then feeds a 1st-order
* IIR low-pass filter:
* filtered += (raw - filtered) >> BATTERY_ADC_LPF_SHIFT
* With LPF_SHIFT=3 (α = 1/8) and 100 Hz tick rate, cutoff ≈ 4 Hz.
*
* 4. Calibration scales and offsets the filtered output:
* vbat_mv = filtered_raw * (VBAT_AREF_MV * VBAT_SCALE_NUM) / 4096
* + cal.vbat_offset_mv
* ibat_ma = filtered_raw * ADC_IBAT_SCALE_MA_PER_COUNT / 1000
* + cal.ibat_offset_ma
* User calibration adjusts cal.vbat_offset_mv to null out divider tolerance.
*
* 5. battery_adc_publish() sends JLINK_TLM_BATTERY (0x82) to Jetson at 1 Hz.
*
* 6. battery_adc_check_pm() monitors for low voltage. If Vbat drops below
* BATTERY_ADC_LOW_MV for BATTERY_ADC_LOW_HOLD_MS, calls
* power_mgmt_notify_battery(vbat_mv) which requests sleep (Issue #467).
*
* Interrupt safety:
* s_dma_buf is written by DMA hardware; battery_adc_tick() reads it with a
* brief __disable_irq() snapshot to prevent torn reads of the 16-bit words.
* All other state is private to the main-loop call path.
*/
#ifndef BATTERY_ADC_H
#define BATTERY_ADC_H
#include <stdint.h>
#include <stdbool.h>
/* ---- Low-pass filter ---- */
/* IIR shift: α = 1/8 → cutoff ≈ 4 Hz at 100 Hz tick rate */
#define BATTERY_ADC_LPF_SHIFT 3u
/* ---- Low-voltage thresholds (mV) ---- */
/* 3S LiPo: 9.0 V cell floor ×3 = 9900 mV full, 9000 mV absolute minimum */
#define BATTERY_ADC_LOW_MV 10200u /* ≈ 15% SoC — warn / throttle */
#define BATTERY_ADC_CRITICAL_MV 9600u /* ≈ 5% SoC — request sleep (#467) */
#define BATTERY_ADC_LOW_HOLD_MS 5000u /* must stay below this long to act */
/* 4S LiPo equivalents (auto-detected when Vbat ≥ 13 V at boot) */
#define BATTERY_ADC_LOW_MV_4S 13600u
#define BATTERY_ADC_CRITICAL_MV_4S 12800u
/* ---- Telemetry rate ---- */
#define BATTERY_ADC_PUBLISH_HZ 1u /* JLINK_TLM_BATTERY TX rate */
/* ---- Calibration struct ---- */
typedef struct {
int16_t vbat_offset_mv; /* additive offset after scale (mV, ±500 clamp) */
int16_t ibat_offset_ma; /* additive offset for current (mA, ±200 clamp) */
uint16_t vbat_scale_num; /* divider numerator override; 0 = use VBAT_SCALE_NUM */
uint16_t vbat_scale_den; /* divider denominator override; 0 = use 1 */
} battery_adc_cal_t;
/* ---- API ---- */
/*
* battery_adc_init() — configure ADC3 continuous-scan + DMA2_Stream0.
* Must be called after __HAL_RCC_ADC3_CLK_ENABLE / GPIO clock enables.
* Call once during system init, before battery_adc_tick().
*/
void battery_adc_init(void);
/*
* battery_adc_tick(now_ms) — average DMA buffer, apply IIR LPF, update state.
* Call from main loop at 10100 Hz. Non-blocking (<5 µs).
*/
void battery_adc_tick(uint32_t now_ms);
/*
* battery_adc_get_voltage_mv() — calibrated, LPF-filtered Vbat in mV.
* Returns 0 if ADC not initialised.
*/
uint32_t battery_adc_get_voltage_mv(void);
/*
* battery_adc_get_current_ma() — calibrated, LPF-filtered Ibat in mA.
* Positive = discharging (load current). Returns 0 if not initialised.
*/
int32_t battery_adc_get_current_ma(void);
/*
* battery_adc_get_raw_voltage_mv() — unfiltered last-tick average (mV).
* Useful for calibration; use filtered version for control logic.
*/
uint32_t battery_adc_get_raw_voltage_mv(void);
/*
* battery_adc_calibrate(cal) — store calibration constants.
* Applies immediately to subsequent battery_adc_tick() calls.
* Pass NULL to reset to defaults (0 offset, default scale).
*/
void battery_adc_calibrate(const battery_adc_cal_t *cal);
/*
* battery_adc_get_calibration(out_cal) — read back current calibration.
*/
void battery_adc_get_calibration(battery_adc_cal_t *out_cal);
/*
* battery_adc_publish(now_ms) — send JLINK_TLM_BATTERY (0x82) frame.
* Rate-limited to BATTERY_ADC_PUBLISH_HZ; safe to call every main loop tick.
*/
void battery_adc_publish(uint32_t now_ms);
/*
* battery_adc_check_pm(now_ms) — evaluate low-voltage thresholds.
* Calls power_mgmt_notify_battery() on sustained critical voltage.
* Call from main loop after battery_adc_tick().
*/
void battery_adc_check_pm(uint32_t now_ms);
/*
* battery_adc_is_low() — true if Vbat below BATTERY_ADC_LOW_MV (warn level).
*/
bool battery_adc_is_low(void);
/*
* battery_adc_is_critical() — true if Vbat below BATTERY_ADC_CRITICAL_MV.
*/
bool battery_adc_is_critical(void);
#endif /* BATTERY_ADC_H */