saltylab-firmware/test/test_battery_adc.c
sl-controls 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

477 lines
16 KiB
C
Raw Permalink 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.

/*
* 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;
}