sl-perception 042c0529a1 feat: Add Issue #375 — adaptive camera power mode manager
Implements a 5-mode FSM for dynamic sensor activation based on speed,
scenario, and battery level — avoids running all 4 CSI cameras + full
sensor suite when unnecessary, saving ~1 GB RAM and significant compute.

Five modes (sensor sets):
  SLEEP  — no sensors       (~150 MB RAM)
  SOCIAL — webcam only      (~400 MB RAM, parked/socialising)
  AWARE  — front CSI + RealSense + LIDAR   (~850 MB RAM, indoor/<5km/h)
  ACTIVE — front+rear CSI + RealSense + LIDAR + UWB  (~1.15 GB, 5-15km/h)
  FULL   — all 4 CSI + RealSense + LIDAR + UWB       (~1.55 GB, >15km/h)

Core library — _camera_power_manager.py (pure Python, no ROS2 deps)
- CameraPowerFSM.update(speed_mps, scenario, battery_pct) → ModeDecision
- Speed-driven upgrades: instant (safety-first)
- Speed-driven downgrades: held for downgrade_hold_s (default 5s, anti-flap)
- Scenario overrides (instant, bypass hysteresis):
  · CROSSING / EMERGENCY → FULL always
  · PARKED → SOCIAL immediately
  · INDOOR → cap at AWARE (never ACTIVE/FULL indoors)
- Battery low cap: battery_pct < threshold → cap at AWARE
- Idle timer: near-zero speed holds at AWARE for idle_to_social_s (30s)
  before dropping to SOCIAL (avoids cycling at traffic lights)

ROS2 node — camera_power_node.py
- Subscribes: /saltybot/speed, /saltybot/scenario, /saltybot/battery_pct
- Publishes: /saltybot/camera_mode (CameraPowerMode, latched, 2 Hz)
- Publishes: /saltybot/camera_cmd/{front,rear,left,right,realsense,lidar,uwb,webcam}
  (std_msgs/Bool, TRANSIENT_LOCAL so late subscribers get last state)
- Logs mode transitions with speed/scenario/battery context

Tests — test/test_camera_power_manager.py: 64/64 passing
- Sensor configs: counts, correct flags per mode, safety invariants
- Speed upgrades: instantaneous at all thresholds, no hold required
- Downgrade hysteresis: hold timer, cancellation on speed spike, hold=0 instant
- Scenario overrides: CROSSING/EMERGENCY/PARKED/INDOOR, all CSIs on crossing
- Battery low: cap at AWARE, threshold boundary
- Idle timer: delay AWARE→SOCIAL, motion resets timer
- Reset, labels, ModeDecision fields
- Integration: full ride scenario (walk→jog→sprint→crossing→indoor→park→low bat)

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-03 16:48:17 -05:00
..