feat(jetson): AprilTag landmark detector — DICT_APRILTAG_36h11 10Hz 6-DOF (issue #191) #197

Merged
sl-jetson merged 1 commits from sl-perception/issue-191-apriltag into main 2026-03-02 11:08:45 -05:00
Collaborator

Summary

  • saltybot_apriltag_msgs: DetectedTag.msg (id, family, decision_margin, corners[8], center, pose, pose_valid) + DetectedTagArray.msg
  • _aruco_utils.py: ROS2-free module — ArucoBackend (cv2 4.6 legacy + 4.7+ ArucoDetector shim), rvec_tvec_to_pose (Rodrigues → Shepperd quaternion)
  • apriltag_node.py: 10 Hz timer; subscribes <image_topic> + derived camera_info; cv2.solvePnP IPPE_SQUARE for 6-DOF pose when intrinsics available; publishes /saltybot/apriltags

Parameters

Parameter Default Description
image_topic /camera/color/image_raw Source image
publish_hz 10.0 Detection rate
tag_size_m 0.10 Physical tag side (metres) for pose
min_margin 10.0 Min corner-span px to keep detection

Test plan

  • 11 unit tests pass (pytest test/test_apriltag.py) — no ROS2 needed
  • ros2 run saltybot_apriltag apriltag_detector — node starts
  • ros2 topic hz /saltybot/apriltags ≈ 10 Hz with camera running
  • Hold a printed 36h11 tag in front of CSI camera — tag_id correct, pose_valid=true
  • Verify quaternion norm = 1.0 and z-distance plausible at ~0.5 m

🤖 Generated with Claude Code

## Summary - **saltybot_apriltag_msgs**: `DetectedTag.msg` (id, family, decision_margin, corners[8], center, pose, pose_valid) + `DetectedTagArray.msg` - **_aruco_utils.py**: ROS2-free module — `ArucoBackend` (cv2 4.6 legacy + 4.7+ `ArucoDetector` shim), `rvec_tvec_to_pose` (Rodrigues → Shepperd quaternion) - **apriltag_node.py**: 10 Hz timer; subscribes `<image_topic>` + derived `camera_info`; `cv2.solvePnP IPPE_SQUARE` for 6-DOF pose when intrinsics available; publishes `/saltybot/apriltags` ## Parameters | Parameter | Default | Description | |---|---|---| | `image_topic` | `/camera/color/image_raw` | Source image | | `publish_hz` | `10.0` | Detection rate | | `tag_size_m` | `0.10` | Physical tag side (metres) for pose | | `min_margin` | `10.0` | Min corner-span px to keep detection | ## Test plan - [x] 11 unit tests pass (`pytest test/test_apriltag.py`) — no ROS2 needed - [ ] `ros2 run saltybot_apriltag apriltag_detector` — node starts - [ ] `ros2 topic hz /saltybot/apriltags` ≈ 10 Hz with camera running - [ ] Hold a printed 36h11 tag in front of CSI camera — `tag_id` correct, `pose_valid=true` - [ ] Verify quaternion norm = 1.0 and z-distance plausible at ~0.5 m 🤖 Generated with [Claude Code](https://claude.com/claude-code)
sl-perception added 1 commit 2026-03-02 11:07:56 -05:00
saltybot_apriltag_msgs (ament_cmake):
• DetectedTag.msg     — tag_id, family, decision_margin, corners[8],
                        center, 6-DOF pose + pose_valid flag
• DetectedTagArray.msg — DetectedTag[], count

saltybot_apriltag (ament_python, single node):
• _aruco_utils.py    — ROS2-free: ArucoBackend (cv2 4.6/4.7+ API shim),
                        rvec_tvec_to_pose (Rodrigues → Shepperd quaternion)
• apriltag_node.py   — 10 Hz timer; subscribes image + latched camera_info;
                        cv2.solvePnP IPPE_SQUARE for 6-DOF pose when K
                        available; publishes /saltybot/apriltags
• test/test_apriltag.py — 11 unit tests (11/11 pass, no ROS2 needed):
                          pose math + rendered tag detection + multi-tag

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
sl-jetson merged commit 7678ddebe2 into main 2026-03-02 11:08:45 -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#197
No description provided.