feat: Phase 2a URDF robot description + static TF for SLAM/Nav2 #50

Merged
seb merged 1 commits from sl-firmware/robot-urdf into main 2026-02-28 23:08:46 -05:00
Collaborator

Summary

  • saltybot_description ROS2 package (ament_python) in jetson/ros2_ws/src/
  • Full kinematic model in urdf/saltybot.urdf.xacro, dimensions from chassis/chassis_frame.scad Rev A
  • config/saltybot_properties.yaml — all robot dimensions as a single source of truth
  • launch/robot_description.launch.py — compiles xacro + runs robot_state_publisher

TF tree published

base_footprint
└── base_link  (z = 0.310m = AXLE_HEIGHT)
    ├── wheel_left_link   (continuous, y = +0.300m)
    ├── wheel_right_link  (continuous, y = −0.300m)
    ├── imu_link          (FC/MPU-6000, x=+0.050m, z=+0.012m)
    ├── stem_link         (visual: 38.1mm EMT, 1.050m)
    └── sensor_head_link  (top of stem)
        ├── laser         (RPLIDAR A1M8 — frame name matches slam_toolbox)
        ├── camera_link   (RealSense D435i — matches realsense2_camera)
        └── camera_{front,left,rear,right}_link  (IMX219, 10° tilt down)

Integration notes

  • Wheel joints require /joint_states from the motor controller bridge (saltybot_bridge)
  • saltybot_cameras/launch/camera_tf.launch.py static TFs are superseded — disable when live to avoid TF conflicts
  • saltybot_bringup/launch/sensors.launch.py placeholder laser/camera TFs should likewise be disabled

Test plan

  • colcon build --packages-select saltybot_description
  • ros2 launch saltybot_description robot_description.launch.py
  • ros2 run tf2_tools view_frames — verify full tree
  • rviz2 — load robot model, confirm geometry matches hardware
  • ros2 topic echo /robot_description — confirm URDF published
## Summary - **`saltybot_description`** ROS2 package (ament_python) in `jetson/ros2_ws/src/` - Full kinematic model in `urdf/saltybot.urdf.xacro`, dimensions from `chassis/chassis_frame.scad` Rev A - `config/saltybot_properties.yaml` — all robot dimensions as a single source of truth - `launch/robot_description.launch.py` — compiles xacro + runs `robot_state_publisher` ## TF tree published ``` base_footprint └── base_link (z = 0.310m = AXLE_HEIGHT) ├── wheel_left_link (continuous, y = +0.300m) ├── wheel_right_link (continuous, y = −0.300m) ├── imu_link (FC/MPU-6000, x=+0.050m, z=+0.012m) ├── stem_link (visual: 38.1mm EMT, 1.050m) └── sensor_head_link (top of stem) ├── laser (RPLIDAR A1M8 — frame name matches slam_toolbox) ├── camera_link (RealSense D435i — matches realsense2_camera) └── camera_{front,left,rear,right}_link (IMX219, 10° tilt down) ``` ## Integration notes - Wheel joints require `/joint_states` from the motor controller bridge (saltybot_bridge) - `saltybot_cameras/launch/camera_tf.launch.py` static TFs are superseded — disable when live to avoid TF conflicts - `saltybot_bringup/launch/sensors.launch.py` placeholder laser/camera TFs should likewise be disabled ## Test plan - [ ] `colcon build --packages-select saltybot_description` - [ ] `ros2 launch saltybot_description robot_description.launch.py` - [ ] `ros2 run tf2_tools view_frames` — verify full tree - [ ] `rviz2` — load robot model, confirm geometry matches hardware - [ ] `ros2 topic echo /robot_description` — confirm URDF published
sl-firmware added 1 commit 2026-02-28 22:58:31 -05:00
Add saltybot_description ROS2 package with full kinematic model:

urdf/saltybot.urdf.xacro
  - base_footprint → base_link (axle_height = 0.310m, from AXLE_HEIGHT SCAD)
  - wheel_left/right_link (continuous, separation=0.600m, radius=0.1015m)
  - imu_link (FC/MPU-6000 at x=+50mm forward, z=+12mm)
  - stem_link (visual: 38.1mm EMT, 1.050m — from stem_battery_clamp.scad)
  - sensor_head_link at top of stem
    - laser (RPLIDAR A1M8, z=COL_H=36mm — frame matches slam_toolbox config)
    - camera_link (RealSense D435i, ARM_R=50mm — matches realsense2_camera)
    - camera_{front,left,rear,right}_link (IMX219, 10° down tilt, ARM_R=50mm
      — positions match camera_tf.launch.py; that file superseded when live)

config/saltybot_properties.yaml
  All dimensions from chassis/chassis_frame.scad + ASSEMBLY.md Rev A.

launch/robot_description.launch.py
  Compiles xacro at launch time, runs robot_state_publisher.
  Publishes /robot_description + /tf_static for all fixed joints.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
seb merged commit 54d3e12c78 into main 2026-02-28 23:08:46 -05:00
seb deleted branch sl-firmware/robot-urdf 2026-02-28 23:08:46 -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#50
No description provided.