feat(jetson): camera health watchdog — 6 streams, WARNING/ERROR, v4l2 reset (issue #198) #199

Merged
sl-jetson merged 1 commits from sl-perception/issue-198-camera-health into main 2026-03-02 11:12:32 -05:00
Collaborator

Summary

  • _camera_state.py — pure-Python CameraState dataclass (no ROS2 imports): on_frame(), age_s, fps(window_s), status(), should_reset() + 30s reset cooldown
  • camera_health_node.py — subscribes 6 image topics (D435i color/depth + 4× IMX219 CSI front/right/rear/left); 1 Hz watchdog tick; WARNING log at >2 s silence; ERROR log + v4l2-ctl --stream-off/--stream-on reset at >10 s (CSI only — D435i is USB); publishes /saltybot/camera_health JSON
  • setup.pycamera_health_monitor console_scripts entry point

JSON output shape

{
  "ts": "2026-03-02T15:00:00Z",
  "cameras": {
    "d435i_color": {"topic": "...", "status": "ok", "age_s": 0.03, "fps": 29.8, "total_frames": 1200},
    "csi_front":   {"topic": "...", "status": "warn", "age_s": 2.4, "fps": 0.0, "total_frames": 450}
  },
  "healthy": 5,
  "degraded": 1,
  "total": 6
}

Test plan

  • 15 unit tests pass (pytest test/test_camera_health.py) — no ROS2 needed
  • ros2 run saltybot_bringup camera_health_monitor — node starts
  • ros2 topic echo /saltybot/camera_health — JSON at 1 Hz
  • Kill one CSI camera; confirm WARNING at 2 s, ERROR at 10 s in logs
  • Confirm D435i streams show null v4l2 device (no reset attempted)

🤖 Generated with Claude Code

## Summary - **`_camera_state.py`** — pure-Python `CameraState` dataclass (no ROS2 imports): `on_frame()`, `age_s`, `fps(window_s)`, `status()`, `should_reset()` + 30s reset cooldown - **`camera_health_node.py`** — subscribes 6 image topics (D435i `color`/`depth` + 4× IMX219 CSI `front`/`right`/`rear`/`left`); 1 Hz watchdog tick; WARNING log at >2 s silence; ERROR log + `v4l2-ctl --stream-off/--stream-on` reset at >10 s (CSI only — D435i is USB); publishes `/saltybot/camera_health` JSON - **`setup.py`** — `camera_health_monitor` console_scripts entry point ## JSON output shape ```json { "ts": "2026-03-02T15:00:00Z", "cameras": { "d435i_color": {"topic": "...", "status": "ok", "age_s": 0.03, "fps": 29.8, "total_frames": 1200}, "csi_front": {"topic": "...", "status": "warn", "age_s": 2.4, "fps": 0.0, "total_frames": 450} }, "healthy": 5, "degraded": 1, "total": 6 } ``` ## Test plan - [x] 15 unit tests pass (`pytest test/test_camera_health.py`) — no ROS2 needed - [ ] `ros2 run saltybot_bringup camera_health_monitor` — node starts - [ ] `ros2 topic echo /saltybot/camera_health` — JSON at 1 Hz - [ ] Kill one CSI camera; confirm WARNING at 2 s, ERROR at 10 s in logs - [ ] Confirm D435i streams show `null` v4l2 device (no reset attempted) 🤖 Generated with [Claude Code](https://claude.com/claude-code)
sl-perception added 1 commit 2026-03-02 11:12:14 -05:00
Adds camera_health_node.py + _camera_state.py to saltybot_bringup:

• _camera_state.py  — pure-Python CameraState dataclass (no ROS2):
                       on_frame(), age_s, fps(window_s), status(),
                       should_reset() + mark_reset() with 30s cooldown

• camera_health_node.py — subscribes 6 image topics (D435i color/depth
                           + 4× IMX219 CSI front/right/rear/left);
                           1 Hz tick: WARNING at >2s silence, ERROR at
                           >10s + v4l2 stream-off/on reset for CSI cams;
                           publishes /saltybot/camera_health JSON with
                           per-camera status, age_s, fps, total_frames

• test/test_camera_health.py — 15 unit tests (15/15 pass, no ROS2 needed)
• setup.py — adds camera_health_monitor console_scripts entry point

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
sl-jetson merged commit b345128427 into main 2026-03-02 11:12:32 -05:00
Sign in to join this conversation.
No Reviewers
No Label
1 Participants
Notifications
Due Date
No due date set.
Dependencies

No dependencies set.

Reference: seb/saltylab-firmware#199
No description provided.