sl-jetson ea26cda76a feat(bridge): battery management node (Issue #125)
Add battery_node.py:
- Subscribes /saltybot/telemetry/battery (JSON from stm32_cmd_node)
- Publishes sensor_msgs/BatteryState on /saltybot/battery at 1 Hz
- SoC source priority: STM32 fuel gauge soc_pct field → fallback to
  3S LiPo voltage curve (12-point lookup with linear interpolation)
- Charging detection: current_ma < -100 mA threshold
- Alert levels: WARNING (20%)→speed 60%, CRITICAL (10%)→speed 30%,
  EMERGENCY (5%)→zero /cmd_vel + /saltybot/arm(False) disarm
- /saltybot/battery/alert JSON topic on threshold crossings
- /saltybot/speed_limit Float32 (0.0-1.0) for nav speed capping
- SQLite history logging: /var/log/saltybot/battery.db, 7-day retention
- Hourly prune timer to keep DB bounded

Add test_battery.py (70+ tests, no ROS2 runtime):
- SoC lookup: all curve points, interpolation, clamping, 3S/4S packs
- Alert level thresholds and transitions for all levels
- Speed factor assignments per alert level
- Charging detection logic
- sensor_msgs/BatteryState field population
- SQLite insert/retrieve/prune (in-memory and on-disk)
- JSON telemetry parsing: normal, charging, soc_pct=0 fallback

Add battery_params.yaml, battery.launch.py.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-02 09:27:06 -05:00

25 lines
1.9 KiB
YAML

# battery_params.yaml — Battery management node configuration (Issue #125)
# ── SQLite history ─────────────────────────────────────────────────────────────
db_path: /var/log/saltybot/battery.db
history_retention_days: 7 # delete records older than N days
# ── Battery pack ──────────────────────────────────────────────────────────────
cell_count: 3 # 3S LiPo (11.1V nominal, 12.6V full)
# ── SoC alert thresholds ──────────────────────────────────────────────────────
warn_pct: 20.0 # WARNING: reduce speed to warn_speed_factor
critical_pct: 10.0 # CRITICAL: reduce speed to critical_speed_factor
emergency_pct: 5.0 # EMERGENCY: full stop + disarm
# ── Speed reduction factors (0.0 = stop, 1.0 = no reduction) ─────────────────
warn_speed_factor: 0.6 # 60% of normal speed at WARNING
critical_speed_factor: 0.3 # 30% of normal speed at CRITICAL
# ── Charging detection ────────────────────────────────────────────────────────
# current_ma below this value → charging detected
charge_detect_ma: -100 # -100 mA threshold (small negative allowed for noise)
# ── Publish rate ──────────────────────────────────────────────────────────────
publish_rate_hz: 1.0 # /saltybot/battery publish frequency