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>
This commit is contained in:
sl-controls 2026-03-07 10:01:02 -05:00
parent e67783f313
commit cc0ffd1999
7 changed files with 1075 additions and 0 deletions

143
include/battery_adc.h Normal file
View File

@ -0,0 +1,143 @@
/*
* battery_adc.h DMA-based battery voltage/current ADC driver (Issue #533)
*
* Hardware:
* ADC3 channel IN11 (PC1) Vbat through 10/1 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 */

View File

@ -59,6 +59,7 @@
/* ---- Telemetry IDs (STM32 → Jetson) ---- */
#define JLINK_TLM_STATUS 0x80u
#define JLINK_TLM_POWER 0x81u /* jlink_tlm_power_t (11 bytes) */
#define JLINK_TLM_BATTERY 0x82u /* jlink_tlm_battery_t (10 bytes, Issue #533) */
/* ---- Telemetry STATUS payload (20 bytes, packed) ---- */
typedef struct __attribute__((packed)) {
@ -88,6 +89,17 @@ typedef struct __attribute__((packed)) {
uint32_t idle_ms; /* ms since last cmd_vel activity */
} jlink_tlm_power_t; /* 11 bytes */
/* ---- Telemetry BATTERY payload (10 bytes, packed) — Issue #533 ---- */
typedef struct __attribute__((packed)) {
uint16_t vbat_mv; /* DMA-sampled LPF-filtered Vbat (mV) */
int16_t ibat_ma; /* DMA-sampled LPF-filtered Ibat (mA, + = discharge) */
uint16_t vbat_raw_mv; /* unfiltered last-tick average (mV) */
uint8_t flags; /* bit0=low, bit1=critical, bit2=4S, bit3=adc_ready */
int8_t cal_offset; /* vbat_offset_mv / 4 (±127 → ±508 mV) */
uint8_t lpf_shift; /* IIR shift factor (α = 1/2^lpf_shift) */
uint8_t soc_pct; /* voltage-based SoC 0100, 255 = unknown */
} jlink_tlm_battery_t; /* 10 bytes */
/* ---- Volatile state (read from main loop) ---- */
typedef struct {
/* Drive command — updated on JLINK_CMD_DRIVE */
@ -149,4 +161,11 @@ void jlink_process(void);
*/
void jlink_send_power_telemetry(const jlink_tlm_power_t *power);
/*
* jlink_send_battery_telemetry(batt) build and transmit JLINK_TLM_BATTERY
* (0x82) frame (16 bytes) at BATTERY_ADC_PUBLISH_HZ (1 Hz).
* Called by battery_adc_publish(); not normally called directly.
*/
void jlink_send_battery_telemetry(const jlink_tlm_battery_t *batt);
#endif /* JLINK_H */

View File

@ -93,4 +93,11 @@ uint16_t power_mgmt_current_ma(void);
/* power_mgmt_idle_ms() — ms elapsed since last power_mgmt_activity() call. */
uint32_t power_mgmt_idle_ms(void);
/*
* power_mgmt_notify_battery(vbat_mv) Issue #467 integration.
* Called by battery_adc_check_pm() after BATTERY_ADC_LOW_HOLD_MS of sustained
* critical voltage. Forces PM_SLEEP_PENDING to protect the LiPo.
*/
void power_mgmt_notify_battery(uint32_t vbat_mv);
#endif /* POWER_MGMT_H */

394
src/battery_adc.c Normal file
View File

@ -0,0 +1,394 @@
/*
* battery_adc.c DMA-based battery voltage/current ADC driver (Issue #533)
*
* Voltage divider calibration, DMA-based continuous sampling, IIR low-pass
* filter, and USART telemetry publish to Jetson via jlink (JLINK_TLM_BATTERY).
* Integrates with power_mgmt for low-battery sleep (Issue #467).
*
* DMA mapping (STM32F7 RM Table 27):
* DMA2_Stream0 Channel2 ADC3 (no conflict: Stream2/Ch4 = USART1_RX)
*
* ADC3 scan sequence:
* Rank 1: IN11 (PC1) Vbat
* Rank 2: IN13 (PC3) Ibat
* Continuous mode, 480-cycle sampling ~14 kSPS per channel @ 13.5 MHz ADC
*
* DMA circular buffer layout (8 × uint16_t, pairs repeat continuously):
* [vbat0, ibat0, vbat1, ibat1, vbat2, ibat2, vbat3, ibat3]
*
* On each battery_adc_tick() call the 4 Vbat and 4 Ibat samples are averaged
* (4× hardware oversampling) then fed into an IIR low-pass filter.
*/
#include "battery_adc.h"
#include "jlink.h"
#include "power_mgmt.h"
#include "config.h"
#include "stm32f7xx_hal.h"
#include <string.h>
/* ---- DMA buffer ---- */
#define ADC_DMA_BUF_LEN 8u /* 4 Vbat/Ibat pairs */
#define ADC_OVERSAMPLE 4u /* pairs per tick average */
static volatile uint16_t s_dma_buf[ADC_DMA_BUF_LEN];
/* ---- HAL handles ---- */
static ADC_HandleTypeDef s_hadc;
static DMA_HandleTypeDef s_hdma;
/* ---- Filtered state (Q0 integer, units: raw ADC counts × 8 for sub-LSB) ---- */
/*
* IIR accumulator: s_lpf_vbat = filtered Vbat in (raw_counts × 8).
* Multiply by 8 gives 3 bits of sub-LSB precision with integer arithmetic.
* On each tick: s_lpf_vbat += (raw_avg - (s_lpf_vbat >> 3)) >> LPF_SHIFT
* Simplified: s_lpf_vbat8 = s_lpf_vbat8 + (raw_avg_x8 - s_lpf_vbat8) >> SHIFT
*/
static uint32_t s_lpf_vbat8 = 0; /* Vbat accumulator × 8 */
static int32_t s_lpf_ibat8 = 0; /* Ibat accumulator × 8 (signed) */
/* ---- Calibrated outputs (updated each tick) ---- */
static uint32_t s_vbat_mv = 0; /* calibrated LPF Vbat (mV) */
static int32_t s_ibat_ma = 0; /* calibrated LPF Ibat (mA) */
static uint32_t s_vbat_raw_mv = 0; /* unfiltered last-tick average (mV) */
/* ---- Calibration ---- */
static battery_adc_cal_t s_cal = {
.vbat_offset_mv = 0,
.ibat_offset_ma = 0,
.vbat_scale_num = 0, /* 0 = use VBAT_SCALE_NUM from config.h */
.vbat_scale_den = 0, /* 0 = use 1 */
};
/* ---- Low-voltage tracking ---- */
static uint32_t s_low_since_ms = 0; /* tick when Vbat first went low */
static bool s_low_active = false; /* currently below LOW_MV threshold */
static bool s_critical_notified = false; /* pm notified for this event */
static uint32_t s_low_mv = BATTERY_ADC_LOW_MV;
static uint32_t s_critical_mv = BATTERY_ADC_CRITICAL_MV;
/* ---- Ready flag ---- */
static bool s_ready = false;
/* ---- Telemetry rate limiting ---- */
static uint32_t s_last_publish_ms = 0;
static bool s_published_once = false; /* force send on first call */
/* ---- Helper: convert raw ADC count to mV ---- */
/*
* Apply voltage divider and calibration:
* vbat_mv = (raw × Vref_mV × scale_num) / (4096 × scale_den)
* + cal.vbat_offset_mv
* Default: Vref=3300 mV, scale_num=VBAT_SCALE_NUM=11, scale_den=1.
*/
static uint32_t raw_to_vbat_mv(uint32_t raw_counts)
{
uint16_t snum = (s_cal.vbat_scale_num != 0u) ? s_cal.vbat_scale_num
: (uint16_t)VBAT_SCALE_NUM;
uint16_t sden = (s_cal.vbat_scale_den != 0u) ? s_cal.vbat_scale_den : 1u;
/* raw_counts × (3300 × 11) / 4096 — keep 32-bit intermediate */
uint32_t mv = (raw_counts * (uint32_t)VBAT_AREF_MV * snum) /
((1u << VBAT_ADC_BITS) * sden);
int32_t cal_mv = (int32_t)mv + (int32_t)s_cal.vbat_offset_mv;
if (cal_mv < 0) cal_mv = 0;
return (uint32_t)cal_mv;
}
/* ---- Helper: convert raw ADC count to mA ---- */
/*
* ADC_IBAT_SCALE = 115 (betaflight ibata_scale units: mA per count × 10).
* Formula: ibat_ma = raw_counts × ADC_IBAT_SCALE / 10 + cal.ibat_offset_ma
* Betaflight ibata_scale is defined as: current = raw * scale / (4096 * 10)
* in units of 100mA per count ibat_ma = raw × ibata_scale * 100 / 4096
*
* With ibata_scale=115: ibat_ma = raw × 115 × 100 / 4096
* raw × 2.808 mA/count
* For raw=4095 (full-scale): ~11,500 mA (11.5 A) appropriate for 3S robot.
*/
static int32_t raw_to_ibat_ma(uint32_t raw_counts)
{
int32_t ma = (int32_t)((raw_counts * (uint32_t)ADC_IBAT_SCALE * 100u) /
(1u << VBAT_ADC_BITS));
ma += (int32_t)s_cal.ibat_offset_ma;
return ma;
}
/* ---- battery_adc_init() ---- */
void battery_adc_init(void)
{
/* ---- GPIO: PC1 (Vbat) and PC3 (Ibat) as analog input ---- */
__HAL_RCC_GPIOC_CLK_ENABLE();
GPIO_InitTypeDef gpio = {0};
gpio.Pin = GPIO_PIN_1 | GPIO_PIN_3;
gpio.Mode = GPIO_MODE_ANALOG;
gpio.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOC, &gpio);
/* ---- DMA2_Stream0 Channel2 → ADC3 (circular, 16-bit, 8 words) ---- */
__HAL_RCC_DMA2_CLK_ENABLE();
s_hdma.Instance = DMA2_Stream0;
s_hdma.Init.Channel = DMA_CHANNEL_2;
s_hdma.Init.Direction = DMA_PERIPH_TO_MEMORY;
s_hdma.Init.PeriphInc = DMA_PINC_DISABLE;
s_hdma.Init.MemInc = DMA_MINC_ENABLE;
s_hdma.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
s_hdma.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
s_hdma.Init.Mode = DMA_CIRCULAR;
s_hdma.Init.Priority = DMA_PRIORITY_LOW;
s_hdma.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
if (HAL_DMA_Init(&s_hdma) != HAL_OK) return;
/* ---- ADC3: continuous scan, DMA, 12-bit, 2 channels ---- */
__HAL_RCC_ADC3_CLK_ENABLE();
s_hadc.Instance = ADC3;
s_hadc.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV8; /* 108/8 ≈ 13.5 MHz */
s_hadc.Init.Resolution = ADC_RESOLUTION_12B;
s_hadc.Init.ScanConvMode = ENABLE; /* scan both channels */
s_hadc.Init.ContinuousConvMode = ENABLE; /* free-running */
s_hadc.Init.DiscontinuousConvMode = DISABLE;
s_hadc.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
s_hadc.Init.ExternalTrigConv = ADC_SOFTWARE_START;
s_hadc.Init.DataAlign = ADC_DATAALIGN_RIGHT;
s_hadc.Init.NbrOfConversion = 2;
s_hadc.Init.DMAContinuousRequests = ENABLE; /* DMA circular */
s_hadc.Init.EOCSelection = ADC_EOC_SEQ_CONV;
__HAL_LINKDMA(&s_hadc, DMA_Handle, s_hdma);
if (HAL_ADC_Init(&s_hadc) != HAL_OK) return;
/* ---- Rank 1: IN11 (PC1) — Vbat ---- */
ADC_ChannelConfTypeDef ch = {0};
ch.Channel = ADC_CHANNEL_11;
ch.Rank = 1;
ch.SamplingTime = ADC_SAMPLETIME_480CYCLES;
if (HAL_ADC_ConfigChannel(&s_hadc, &ch) != HAL_OK) return;
/* ---- Rank 2: IN13 (PC3) — Ibat ---- */
ch.Channel = ADC_CHANNEL_13;
ch.Rank = 2;
ch.SamplingTime = ADC_SAMPLETIME_480CYCLES;
if (HAL_ADC_ConfigChannel(&s_hadc, &ch) != HAL_OK) return;
/* ---- Detect battery cell count at init for correct thresholds ---- */
/*
* Note: at init Vbat may not be settled; thresholds are updated after
* first tick once LPF has stabilised. Set 4S thresholds if voltage
* detected 13 V in battery_adc_tick() on first valid reading.
*/
/* ---- Start continuous DMA conversion ---- */
if (HAL_ADC_Start_DMA(&s_hadc, (uint32_t *)s_dma_buf, ADC_DMA_BUF_LEN)
!= HAL_OK) return;
s_ready = true;
}
/* ---- battery_adc_tick() ---- */
void battery_adc_tick(uint32_t now_ms)
{
if (!s_ready) return;
(void)now_ms; /* captured for caller context; may be used for future rate ctrl */
/* ---- Snapshot DMA buffer with IRQ guard to prevent torn reads ---- */
uint16_t snap[ADC_DMA_BUF_LEN];
uint32_t primask = __get_PRIMASK();
__disable_irq();
memcpy(snap, (void *)s_dma_buf, sizeof(snap));
__set_PRIMASK(primask);
/* ---- Average 4 Vbat and 4 Ibat samples (interleaved pairs) ---- */
uint32_t vbat_sum = 0u;
uint32_t ibat_sum = 0u;
for (uint32_t i = 0u; i < ADC_DMA_BUF_LEN; i += 2u) {
vbat_sum += snap[i]; /* even indices: Vbat (rank 1) */
ibat_sum += snap[i + 1u]; /* odd indices: Ibat (rank 2) */
}
uint32_t vbat_avg = vbat_sum / ADC_OVERSAMPLE; /* 04095 */
uint32_t ibat_avg = ibat_sum / ADC_OVERSAMPLE;
/* ---- Raw (unfiltered) calibrated voltage — for calibration query ---- */
s_vbat_raw_mv = raw_to_vbat_mv(vbat_avg);
/* ---- IIR low-pass filter ---- */
/*
* Accumulator stores value × 8 for sub-LSB precision.
* Update: acc8 += (raw × 8 - acc8) >> LPF_SHIFT
* Result: filtered_raw = acc8 >> 3
*
* With LPF_SHIFT=3: α = 1/(1+8) 0.111 cutoff 4 Hz at 100 Hz tick.
*/
s_lpf_vbat8 += ((vbat_avg << 3u) - s_lpf_vbat8) >> BATTERY_ADC_LPF_SHIFT;
s_lpf_ibat8 += (((int32_t)ibat_avg << 3u) - s_lpf_ibat8)
>> BATTERY_ADC_LPF_SHIFT;
uint32_t vbat_filtered = s_lpf_vbat8 >> 3u; /* back to ADC counts */
uint32_t ibat_filtered = (uint32_t)((s_lpf_ibat8 < 0 ? 0 : s_lpf_ibat8) >> 3u);
/* ---- Apply calibration and convert to engineering units ---- */
s_vbat_mv = raw_to_vbat_mv(vbat_filtered);
s_ibat_ma = raw_to_ibat_ma(ibat_filtered);
/* ---- Auto-set thresholds based on detected cell count ---- */
/*
* Detect 4S (Vbat 13 V) vs 3S (<13 V). Only update thresholds once
* after initial settling (first non-zero filtered reading).
*/
static bool s_thresholds_set = false;
if (!s_thresholds_set && s_vbat_mv > 500u) {
if (s_vbat_mv >= 13000u) {
s_low_mv = BATTERY_ADC_LOW_MV_4S;
s_critical_mv = BATTERY_ADC_CRITICAL_MV_4S;
}
/* else keep 3S defaults set at file scope */
s_thresholds_set = true;
}
}
/* ---- battery_adc_get_voltage_mv() ---- */
uint32_t battery_adc_get_voltage_mv(void)
{
return s_vbat_mv;
}
/* ---- battery_adc_get_current_ma() ---- */
int32_t battery_adc_get_current_ma(void)
{
return s_ibat_ma;
}
/* ---- battery_adc_get_raw_voltage_mv() ---- */
uint32_t battery_adc_get_raw_voltage_mv(void)
{
return s_vbat_raw_mv;
}
/* ---- battery_adc_calibrate() ---- */
void battery_adc_calibrate(const battery_adc_cal_t *cal)
{
if (cal == NULL) {
/* Reset to defaults */
s_cal.vbat_offset_mv = 0;
s_cal.ibat_offset_ma = 0;
s_cal.vbat_scale_num = 0;
s_cal.vbat_scale_den = 0;
return;
}
/* Clamp offsets to prevent runaway calibration values */
int16_t voff = cal->vbat_offset_mv;
if (voff > 500) voff = 500;
if (voff < -500) voff = -500;
int16_t ioff = cal->ibat_offset_ma;
if (ioff > 200) ioff = 200;
if (ioff < -200) ioff = -200;
s_cal.vbat_offset_mv = voff;
s_cal.ibat_offset_ma = ioff;
s_cal.vbat_scale_num = cal->vbat_scale_num;
s_cal.vbat_scale_den = cal->vbat_scale_den;
}
/* ---- battery_adc_get_calibration() ---- */
void battery_adc_get_calibration(battery_adc_cal_t *out_cal)
{
if (out_cal != NULL) {
*out_cal = s_cal;
}
}
/* ---- battery_adc_publish() ---- */
/*
* Sends JLINK_TLM_BATTERY (0x82) frame to Jetson at BATTERY_ADC_PUBLISH_HZ.
*
* Payload (jlink_tlm_battery_t, 10 bytes packed):
* vbat_mv uint16 calibrated LPF voltage (mV)
* ibat_ma int16 calibrated LPF current (mA)
* vbat_raw_mv uint16 unfiltered last-tick voltage (mV)
* flags uint8 bit0=low, bit1=critical, bit2=4S detected, bit3=ready
* cal_offset int8 vbat_offset_mv / 4 (compressed, ±127 ±508 mV)
* lpf_shift uint8 BATTERY_ADC_LPF_SHIFT value (for Jetson info)
* soc_pct uint8 voltage-based SoC estimate (0-100, 255=unknown)
*/
void battery_adc_publish(uint32_t now_ms)
{
if (!s_ready) return;
uint32_t period_ms = 1000u / BATTERY_ADC_PUBLISH_HZ;
if (s_published_once && (now_ms - s_last_publish_ms) < period_ms) return;
s_last_publish_ms = now_ms;
s_published_once = true;
/* Build SoC estimate (voltage-based) */
uint8_t soc = 255u; /* unknown */
if (s_vbat_mv > 500u) {
uint32_t v_min, v_max;
if (s_vbat_mv >= 13000u) {
v_min = 13200u; v_max = 16800u; /* 4S */
} else {
v_min = 9900u; v_max = 12600u; /* 3S */
}
if (s_vbat_mv <= v_min) {
soc = 0u;
} else if (s_vbat_mv >= v_max) {
soc = 100u;
} else {
soc = (uint8_t)(((s_vbat_mv - v_min) * 100u) / (v_max - v_min));
}
}
/* Flags byte */
uint8_t flags = 0u;
if (s_vbat_mv > 0u && s_vbat_mv < s_low_mv) flags |= 0x01u;
if (s_vbat_mv > 0u && s_vbat_mv < s_critical_mv) flags |= 0x02u;
if (s_low_mv == BATTERY_ADC_LOW_MV_4S) flags |= 0x04u;
if (s_ready) flags |= 0x08u;
/* Build JLINK_TLM_BATTERY frame via jlink_send_battery_telemetry() */
jlink_tlm_battery_t tlm = {
.vbat_mv = (uint16_t)(s_vbat_mv & 0xFFFFu),
.ibat_ma = (int16_t) (s_ibat_ma & 0xFFFF),
.vbat_raw_mv = (uint16_t)(s_vbat_raw_mv & 0xFFFFu),
.flags = flags,
.cal_offset = (int8_t) (s_cal.vbat_offset_mv / 4),
.lpf_shift = (uint8_t) BATTERY_ADC_LPF_SHIFT,
.soc_pct = soc,
};
jlink_send_battery_telemetry(&tlm);
}
/* ---- battery_adc_check_pm() ---- */
void battery_adc_check_pm(uint32_t now_ms)
{
if (!s_ready || s_vbat_mv == 0u) return;
bool below_low = (s_vbat_mv < s_low_mv);
bool below_critical = (s_vbat_mv < s_critical_mv);
/* Track first entry below low threshold */
if (below_low && !s_low_active) {
s_low_active = true;
s_low_since_ms = now_ms;
s_critical_notified = false;
} else if (!below_low) {
s_low_active = false;
s_critical_notified = false;
}
/* Notify power management on sustained critical voltage */
if (below_critical && !s_critical_notified &&
(now_ms - s_low_since_ms) >= BATTERY_ADC_LOW_HOLD_MS) {
s_critical_notified = true;
power_mgmt_notify_battery(s_vbat_mv);
}
}
/* ---- battery_adc_is_low() ---- */
bool battery_adc_is_low(void)
{
return (s_ready && s_vbat_mv > 0u && s_vbat_mv < s_low_mv);
}
/* ---- battery_adc_is_critical() ---- */
bool battery_adc_is_critical(void)
{
return (s_ready && s_vbat_mv > 0u && s_vbat_mv < s_critical_mv);
}

View File

@ -342,3 +342,28 @@ void jlink_send_power_telemetry(const jlink_tlm_power_t *power)
jlink_tx_locked(frame, sizeof(frame));
}
/* ---- jlink_send_battery_telemetry() — Issue #533 ---- */
void jlink_send_battery_telemetry(const jlink_tlm_battery_t *batt)
{
/*
* Frame: [STX][LEN][0x82][10 bytes BATTERY][CRC_hi][CRC_lo][ETX]
* LEN = 1 (CMD) + 10 (payload) = 11; total = 16 bytes
* At 921600 baud: 16×10/921600 0.17 ms safe to block.
*/
static uint8_t frame[16];
const uint8_t plen = (uint8_t)sizeof(jlink_tlm_battery_t); /* 10 */
const uint8_t len = 1u + plen; /* 11 */
frame[0] = JLINK_STX;
frame[1] = len;
frame[2] = JLINK_TLM_BATTERY;
memcpy(&frame[3], batt, plen);
uint16_t crc = crc16_xmodem(&frame[2], len);
frame[3 + plen] = (uint8_t)(crc >> 8);
frame[3 + plen + 1] = (uint8_t)(crc & 0xFFu);
frame[3 + plen + 2] = JLINK_ETX;
jlink_tx_locked(frame, sizeof(frame));
}

View File

@ -252,3 +252,14 @@ PowerState power_mgmt_tick(uint32_t now_ms)
return s_state;
}
/* Issue #467: battery low-voltage emergency sleep integration */
static uint32_t s_batt_critical_mv = 0u;
void power_mgmt_notify_battery(uint32_t vbat_mv)
{
s_batt_critical_mv = vbat_mv;
if (s_state == PM_SLEEPING || s_state == PM_SLEEP_PENDING) return;
s_sleep_req = true;
s_fade_start = HAL_GetTick();
}

476
test/test_battery_adc.c Normal file
View File

@ -0,0 +1,476 @@
/*
* test_battery_adc.c Unit tests for battery_adc driver (Issue #533)
*
* Tests run on host (Linux/macOS) with stub HAL functions.
* Build: gcc -I../include -DTEST_HOST -o test_battery_adc test_battery_adc.c
*
* Coverage:
* 1. raw_to_vbat_mv default scale (VBAT_SCALE_NUM=11, VBAT_AREF_MV=3300)
* 2. raw_to_vbat_mv calibration offset (+100 mV, -100 mV)
* 3. raw_to_vbat_mv calibration scale override
* 4. IIR LPF convergence step input settles within N ticks
* 5. IIR LPF LPF_SHIFT=3 gives α 1/8 per tick
* 6. SoC estimate 3S LiPo 0% / 100% / midpoint
* 7. SoC estimate 4S LiPo 0% / 100%
* 8. battery_adc_is_low() / is_critical() flags
* 9. battery_adc_check_pm() below threshold for < HOLD_MS: no notify
* 10. battery_adc_check_pm() below threshold for >= HOLD_MS: notify fires
* 11. battery_adc_check_pm() recovery clears state
* 12. calibrate(NULL) resets to defaults
* 13. calibrate() clamps offset to ±500 mV
* 14. publish() rate-limit not sent before PUBLISH_HZ period
* 15. publish() rate-limit sent after period elapses
*/
#include <stdio.h>
#include <stdint.h>
#include <stdbool.h>
#include <string.h>
#include <assert.h>
/* ---- Minimal HAL stubs (guards real header, provides needed types) ---- */
/* Must appear before any #include that could pull in stm32f7xx_hal.h */
#define STM32F7XX_HAL_H
#define HAL_OK 0
#define ENABLE 1
#define DISABLE 0
typedef uint32_t GPIO_TypeDef;
typedef struct { uint32_t Pin, Mode, Pull, Speed; } GPIO_InitTypeDef;
typedef uint32_t DMA_Stream_TypeDef;
typedef struct {
uint32_t Channel, Direction, PeriphInc, MemInc;
uint32_t PeriphDataAlignment, MemDataAlignment, Mode, Priority, FIFOMode;
} DMA_InitTypeDef;
typedef struct { DMA_Stream_TypeDef *Instance; DMA_InitTypeDef Init; } DMA_HandleTypeDef;
typedef uint32_t ADC_TypeDef;
typedef struct {
uint32_t ClockPrescaler, Resolution, ScanConvMode, ContinuousConvMode;
uint32_t DiscontinuousConvMode, ExternalTrigConvEdge, ExternalTrigConv;
uint32_t DataAlign, NbrOfConversion, DMAContinuousRequests, EOCSelection;
} ADC_InitTypeDef;
typedef struct { ADC_TypeDef *Instance; ADC_InitTypeDef Init; DMA_HandleTypeDef *DMA_Handle; } ADC_HandleTypeDef;
typedef struct { uint32_t Channel, Rank, SamplingTime; } ADC_ChannelConfTypeDef;
#define GPIO_PIN_1 (1u<<1)
#define GPIO_PIN_3 (1u<<3)
#define GPIO_MODE_ANALOG 0
#define GPIO_NOPULL 0
#define GPIO_SPEED_FREQ_HIGH 0
#define DMA_CHANNEL_2 0
#define DMA_PERIPH_TO_MEMORY 0
#define DMA_PINC_DISABLE 0
#define DMA_MINC_ENABLE 0
#define DMA_PDATAALIGN_HALFWORD 0
#define DMA_MDATAALIGN_HALFWORD 0
#define DMA_CIRCULAR 0
#define DMA_PRIORITY_LOW 0
#define DMA_FIFOMODE_DISABLE 0
#define ADC_CLOCK_SYNC_PCLK_DIV8 0
#define ADC_RESOLUTION_12B 0
#define ADC_EXTERNALTRIGCONVEDGE_NONE 0
#define ADC_SOFTWARE_START 0
#define ADC_DATAALIGN_RIGHT 0
#define ADC_EOC_SEQ_CONV 0
#define ADC_CHANNEL_11 11
#define ADC_CHANNEL_13 13
#define ADC_SAMPLETIME_480CYCLES 0
static uint32_t _gpioc_s, _dma2s0_s, _adc3_s;
#define GPIOC ((GPIO_TypeDef *)&_gpioc_s)
#define DMA2_Stream0 ((DMA_Stream_TypeDef *)&_dma2s0_s)
#define ADC3 ((ADC_TypeDef *)&_adc3_s)
#define __HAL_RCC_GPIOC_CLK_ENABLE() ((void)0)
#define __HAL_RCC_DMA2_CLK_ENABLE() ((void)0)
#define __HAL_RCC_ADC3_CLK_ENABLE() ((void)0)
#define __HAL_LINKDMA(hadc, field, hdma) ((hadc)->DMA_Handle = &(hdma))
static inline int HAL_GPIO_Init(void *p, GPIO_InitTypeDef *g){(void)p;(void)g;return 0;}
static inline int HAL_DMA_Init(DMA_HandleTypeDef *h){(void)h;return HAL_OK;}
static inline int HAL_ADC_Init(ADC_HandleTypeDef *h){(void)h;return HAL_OK;}
static inline int HAL_ADC_ConfigChannel(ADC_HandleTypeDef *h,ADC_ChannelConfTypeDef *c){(void)h;(void)c;return HAL_OK;}
static inline int HAL_ADC_Start_DMA(ADC_HandleTypeDef *h,uint32_t *b,uint32_t n){(void)h;(void)b;(void)n;return HAL_OK;}
static inline uint32_t __get_PRIMASK(void){return 0;}
static inline void __disable_irq(void){}
static inline void __set_PRIMASK(uint32_t v){(void)v;}
/* Config constants (mirror config.h) */
#define VBAT_SCALE_NUM 11
#define VBAT_AREF_MV 3300
#define VBAT_ADC_BITS 12
#define ADC_IBAT_SCALE 115
/* power_mgmt stub */
static uint32_t g_pm_notify_vbat = 0;
static int g_pm_notify_count = 0;
void power_mgmt_notify_battery(uint32_t vbat_mv) {
g_pm_notify_vbat = vbat_mv;
g_pm_notify_count++;
}
/* jlink stubs — must appear before battery_adc.c which calls these */
static int g_jlink_send_count = 0;
/* jlink_tlm_battery_t is defined in jlink.h; replicate minimal version here */
typedef struct __attribute__((packed)) {
uint16_t vbat_mv; int16_t ibat_ma; uint16_t vbat_raw_mv;
uint8_t flags; int8_t cal_offset; uint8_t lpf_shift; uint8_t soc_pct;
} jlink_tlm_battery_t;
void jlink_send_battery_telemetry(const jlink_tlm_battery_t *b) {
(void)b; g_jlink_send_count++;
}
/* ---- Include driver source directly for white-box testing ---- */
/* jlink.h and power_mgmt.h includes are bypassed by the stubs above */
#define JLINK_H /* block jlink.h inclusion in battery_adc.c */
#define POWER_MGMT_H /* block power_mgmt.h inclusion in battery_adc.c */
#include "../src/battery_adc.c"
/* ---- Test helpers ---- */
static int g_pass = 0, g_fail = 0;
#define TEST(name) do { printf(" %-55s", name); } while(0)
#define PASS() do { g_pass++; printf("PASS\n"); } while(0)
#define FAIL(msg) do { g_fail++; printf("FAIL — %s\n", msg); } while(0)
#define ASSERT_EQ(a,b,msg) do { if ((a)==(b)) PASS(); else FAIL(msg); } while(0)
#define ASSERT_NEAR(a,b,tol,msg) do { \
int32_t _d = (int32_t)(a) - (int32_t)(b); \
if (_d < 0) _d = -_d; \
if (_d <= (int32_t)(tol)) PASS(); else FAIL(msg); } while(0)
#define ASSERT_TRUE(x,msg) ASSERT_EQ(!!(x), 1, msg)
#define ASSERT_FALSE(x,msg) ASSERT_EQ(!!(x), 0, msg)
/* ---- Reset driver private state for each test ---- */
static void reset_driver(void)
{
s_vbat_mv = 0;
s_ibat_ma = 0;
s_vbat_raw_mv = 0;
s_lpf_vbat8 = 0;
s_lpf_ibat8 = 0;
s_low_active = false;
s_low_since_ms = 0;
s_critical_notified = false;
s_last_publish_ms = 0;
s_published_once = false;
s_low_mv = BATTERY_ADC_LOW_MV;
s_critical_mv = BATTERY_ADC_CRITICAL_MV;
s_ready = true; /* simulate successful init */
battery_adc_calibrate(NULL);
g_pm_notify_vbat = 0;
g_pm_notify_count = 0;
g_jlink_send_count = 0;
/* Reset thresholds_set flag — hack: zero the static inside battery_adc_tick */
/* Re-init will re-detect 3S/4S on next tick */
}
/* ---- Helper: directly inject filtered values (bypass DMA) ---- */
static void inject_voltage_mv(uint32_t mv)
{
/* Back-calculate raw count from mV = raw × (3300 × 11) / 4096 */
uint32_t raw = (mv * (1u << VBAT_ADC_BITS)) /
(VBAT_AREF_MV * VBAT_SCALE_NUM);
/* Set LPF accumulators to fully settled value */
s_lpf_vbat8 = raw << 3u;
/* Force output update */
s_vbat_mv = raw_to_vbat_mv(raw);
s_vbat_raw_mv = s_vbat_mv;
/* Auto-set 4S thresholds if needed */
if (s_vbat_mv >= 13000u) {
s_low_mv = BATTERY_ADC_LOW_MV_4S;
s_critical_mv = BATTERY_ADC_CRITICAL_MV_4S;
} else {
s_low_mv = BATTERY_ADC_LOW_MV;
s_critical_mv = BATTERY_ADC_CRITICAL_MV;
}
}
/* ---- Tests ---- */
static void test_raw_to_vbat_default(void)
{
TEST("raw_to_vbat_mv: 0 count → 0 mV");
ASSERT_EQ(raw_to_vbat_mv(0), 0u, "zero raw should be 0 mV");
TEST("raw_to_vbat_mv: 4095 count → 3300×11 mV");
uint32_t expected = (4095u * 3300u * 11u) / 4096u;
ASSERT_NEAR(raw_to_vbat_mv(4095), expected, 2u, "full-scale raw");
TEST("raw_to_vbat_mv: midpoint 2048 → ~8812 mV (3S half-charge)");
uint32_t mid = (2048u * 3300u * 11u) / 4096u;
ASSERT_NEAR(raw_to_vbat_mv(2048), mid, 2u, "midpoint raw");
}
static void test_calibration_offset(void)
{
reset_driver();
battery_adc_cal_t cal = {0};
TEST("cal offset +100 mV increases output by ~100 mV");
cal.vbat_offset_mv = 100;
battery_adc_calibrate(&cal);
uint32_t base = raw_to_vbat_mv(1000);
cal.vbat_offset_mv = 0;
battery_adc_calibrate(&cal);
uint32_t no_offset = raw_to_vbat_mv(1000);
ASSERT_NEAR(base - no_offset, 100u, 2u, "+100 mV offset delta");
TEST("cal offset -100 mV decreases output by ~100 mV");
cal.vbat_offset_mv = -100;
battery_adc_calibrate(&cal);
uint32_t neg_offset = raw_to_vbat_mv(1000);
cal.vbat_offset_mv = 0;
battery_adc_calibrate(&cal);
uint32_t delta = no_offset - neg_offset;
ASSERT_NEAR(delta, 100u, 2u, "-100 mV offset delta");
TEST("cal offset clamp: +600 clamped to +500 mV");
cal.vbat_offset_mv = 600;
battery_adc_calibrate(&cal);
battery_adc_get_calibration(&cal);
ASSERT_EQ(cal.vbat_offset_mv, 500, "clamp to +500");
}
static void test_calibration_scale_override(void)
{
reset_driver();
battery_adc_cal_t cal = {0};
TEST("scale override: num=22, den=2 same as default (11/1)");
cal.vbat_scale_num = 22;
cal.vbat_scale_den = 2;
battery_adc_calibrate(&cal);
uint32_t scaled = raw_to_vbat_mv(2000);
cal.vbat_scale_num = 0; cal.vbat_scale_den = 0;
battery_adc_calibrate(&cal);
uint32_t dflt = raw_to_vbat_mv(2000);
ASSERT_NEAR(scaled, dflt, 2u, "22/2 == 11/1 scale");
}
static void test_lpf_convergence(void)
{
reset_driver();
/* Step from 0 to a target: check convergence after N ticks */
/* Target raw = 3000 counts ≈ 27,000 mV @ 11:1 divider */
uint16_t target_raw = 3000u;
/* Fill DMA buffer with target value */
uint16_t fake_buf[8];
for (int i = 0; i < 8; i += 2) { fake_buf[i] = target_raw; fake_buf[i+1] = 0; }
/* Manually tick IIR 80 times (should be ~99% settled in 36 ticks) */
for (int i = 0; i < 80; i++) {
uint32_t avg = target_raw;
s_lpf_vbat8 += ((avg << 3u) - s_lpf_vbat8) >> BATTERY_ADC_LPF_SHIFT;
}
uint32_t filtered = s_lpf_vbat8 >> 3u;
TEST("IIR LPF 80-tick convergence within 2% of target");
uint32_t diff = (filtered > target_raw) ? (filtered - target_raw) : (target_raw - filtered);
ASSERT_TRUE(diff <= target_raw / 50u, "LPF settled to within 2%");
}
static void test_lpf_alpha(void)
{
TEST("IIR LPF_SHIFT=3 → α ≈ 1/8 per step");
/* After 1 tick from 0 to 8000 (×8): delta = 8000/8 = 1000 */
uint32_t acc = 0;
uint32_t step = 8000u;
acc += (step - acc) >> BATTERY_ADC_LPF_SHIFT;
/* Expected: acc = 8000/8 = 1000 */
ASSERT_NEAR(acc, 1000u, 2u, "one-step IIR response");
}
static void test_soc_3s(void)
{
reset_driver();
TEST("SoC 3S: 9900 mV → 0%");
inject_voltage_mv(9900u);
s_vbat_mv = 9900u;
/* Run publish logic inline */
uint8_t soc = 255u;
{ uint32_t v = 9900u, vmin = 9900u, vmax = 12600u;
soc = (v <= vmin) ? 0u : (v >= vmax ? 100u :
(uint8_t)(((v - vmin) * 100u) / (vmax - vmin))); }
ASSERT_EQ(soc, 0u, "9900 mV = 0%");
TEST("SoC 3S: 12600 mV → 100%");
{ uint32_t v = 12600u, vmin = 9900u, vmax = 12600u;
soc = (v <= vmin) ? 0u : (v >= vmax ? 100u :
(uint8_t)(((v - vmin) * 100u) / (vmax - vmin))); }
ASSERT_EQ(soc, 100u, "12600 mV = 100%");
TEST("SoC 3S: 11250 mV → ~50%");
{ uint32_t v = 11250u, vmin = 9900u, vmax = 12600u;
soc = (uint8_t)(((v - vmin) * 100u) / (vmax - vmin)); }
ASSERT_NEAR(soc, 50u, 2u, "11250 mV ≈ 50%");
}
static void test_soc_4s(void)
{
TEST("SoC 4S: 13200 mV → 0%");
uint8_t soc;
{ uint32_t v = 13200u, vmin = 13200u, vmax = 16800u;
soc = (v <= vmin) ? 0u : 100u; }
ASSERT_EQ(soc, 0u, "13200 mV 4S = 0%");
TEST("SoC 4S: 16800 mV → 100%");
{ uint32_t v = 16800u, vmin = 13200u, vmax = 16800u;
soc = (v >= vmax) ? 100u : 0u; }
ASSERT_EQ(soc, 100u, "16800 mV 4S = 100%");
}
static void test_is_low_critical_flags(void)
{
reset_driver();
TEST("is_low(): false when Vbat above LOW_MV threshold");
inject_voltage_mv(11000u); /* well above 10200 mV LOW_MV */
ASSERT_FALSE(battery_adc_is_low(), "11 V not low");
TEST("is_low(): true when Vbat below LOW_MV");
inject_voltage_mv(9800u);
ASSERT_TRUE(battery_adc_is_low(), "9.8 V is low");
TEST("is_critical(): false when above CRITICAL_MV");
inject_voltage_mv(10000u); /* above 9600 */
ASSERT_FALSE(battery_adc_is_critical(), "10 V not critical");
TEST("is_critical(): true when below CRITICAL_MV");
inject_voltage_mv(9400u);
ASSERT_TRUE(battery_adc_is_critical(), "9.4 V is critical");
}
static void test_check_pm_no_notify_short(void)
{
reset_driver();
TEST("check_pm: no notify when below critical < HOLD_MS");
inject_voltage_mv(9400u); /* below CRITICAL_MV=9600 */
/* Call check_pm at t=0 */
s_low_active = false;
s_low_since_ms = 0;
s_critical_notified = false;
battery_adc_check_pm(0u);
battery_adc_check_pm(1000u); /* 1 second — not yet 5 s */
battery_adc_check_pm(4000u); /* 4 seconds */
ASSERT_EQ(g_pm_notify_count, 0, "no notify before HOLD_MS");
}
static void test_check_pm_notify_after_hold(void)
{
reset_driver();
TEST("check_pm: notify fires after HOLD_MS sustained critical voltage");
inject_voltage_mv(9400u);
battery_adc_check_pm(0u);
battery_adc_check_pm(5001u); /* just past HOLD_MS=5000 */
ASSERT_EQ(g_pm_notify_count, 1, "notify fires once after hold");
}
static void test_check_pm_notify_only_once(void)
{
reset_driver();
inject_voltage_mv(9400u);
battery_adc_check_pm(0u);
battery_adc_check_pm(5001u);
battery_adc_check_pm(6000u); /* still critical */
battery_adc_check_pm(7000u);
TEST("check_pm: notify fires only once per low event");
ASSERT_EQ(g_pm_notify_count, 1, "notify not repeated");
}
static void test_check_pm_recovery(void)
{
reset_driver();
inject_voltage_mv(9400u);
battery_adc_check_pm(0u);
battery_adc_check_pm(5001u); /* first event fires */
/* Voltage recovers */
inject_voltage_mv(11000u);
battery_adc_check_pm(6000u); /* recovery tick */
/* Voltage drops again */
inject_voltage_mv(9400u);
battery_adc_check_pm(7000u); /* new low event starts */
battery_adc_check_pm(12001u); /* 5 s after new event */
TEST("check_pm: recovery + re-trigger fires notify again");
ASSERT_EQ(g_pm_notify_count, 2, "two events = two notifies");
}
static void test_calibrate_null_reset(void)
{
reset_driver();
battery_adc_cal_t cal = { .vbat_offset_mv = 200, .ibat_offset_ma = 50,
.vbat_scale_num = 10, .vbat_scale_den = 1 };
battery_adc_calibrate(&cal);
battery_adc_calibrate(NULL);
battery_adc_get_calibration(&cal);
TEST("calibrate(NULL): resets vbat_offset to 0");
ASSERT_EQ(cal.vbat_offset_mv, 0, "offset reset");
TEST("calibrate(NULL): resets scale_num to 0 (use default)");
ASSERT_EQ(cal.vbat_scale_num, 0, "scale_num reset");
}
static void test_publish_rate_limit(void)
{
reset_driver();
inject_voltage_mv(11000u);
s_ready = true;
g_jlink_send_count = 0;
uint32_t period_ms = 1000u / BATTERY_ADC_PUBLISH_HZ;
battery_adc_publish(0u);
TEST("publish: first call always sends");
ASSERT_EQ(g_jlink_send_count, 1, "first send");
battery_adc_publish(period_ms - 1u);
TEST("publish: no send before period elapses");
ASSERT_EQ(g_jlink_send_count, 1, "no premature send");
battery_adc_publish(period_ms + 1u);
TEST("publish: send after period elapses");
ASSERT_EQ(g_jlink_send_count, 2, "send after period");
}
/* ---- main ---- */
int main(void)
{
printf("=== test_battery_adc (Issue #533) ===\n\n");
test_raw_to_vbat_default();
test_calibration_offset();
test_calibration_scale_override();
test_lpf_convergence();
test_lpf_alpha();
test_soc_3s();
test_soc_4s();
test_is_low_critical_flags();
test_check_pm_no_notify_short();
test_check_pm_notify_after_hold();
test_check_pm_notify_only_once();
test_check_pm_recovery();
test_calibrate_null_reset();
test_publish_rate_limit();
printf("\n=== Results: %d passed, %d failed ===\n", g_pass, g_fail);
return (g_fail == 0) ? 0 : 1;
}