Position in the full course
This is the fifth step of the course.
The full learning order is:
1. ROS 2 node/topic/launch review
2. TF2 frame concept
3. Static sensor frames
4. Dynamic odometry frame
5. URDF + robot_state_publisher
6. SLAM mapping
7. AMCL localization
8. Nav2 path planning
9. RViz goal navigation
10. TF2 debugging in Nav2
In Step 3, you manually published static sensor frames:
base_link → base_laser
base_link → camera_link
base_link → imu_link
In Step 4, you published a dynamic odometry transform:
odom → base_link
In Step 5, you will learn a cleaner way to describe the robot structure:
URDF + robot_state_publisher
1. Learning objectives
After this module, you should be able to:
- Explain what URDF is.
- Explain why URDF is useful for robot TF frames.
- Create a simple AMR URDF model.
- Define robot links in URDF.
- Define robot joints in URDF.
- Use
robot_state_publisherto publish robot TF frames. - Use
joint_state_publisher_guito test movable joints. - Visualize the robot model in RViz2.
- Understand how URDF supports Nav2 TF setup.
- Understand when to use URDF instead of manual static transform publishers.
2. Suggested teaching duration
Suggested duration: 2 hours
| Time | Activity |
| ----------- | -------------------------------- |
| 0–15 min | Review Step 3 and Step 4 TF tree |
| 15–30 min | Explain URDF, link, and joint |
| 30–55 min | Create simple AMR URDF |
| 55–75 min | Launch robot_state_publisher |
| 75–95 min | Visualize robot model in RViz2 |
| 95–110 min | Check TF frames |
| 110–120 min | Summary and homework |
3. Why you need URDF
In Step 3, you published static sensor frames using commands like:
ros2 run tf2_ros static_transform_publisher \
--x 0.20 --y 0.00 --z 0.15 \
--roll 0 --pitch 0 --yaw 0 \
--frame-id base_link \
--child-frame-id base_laser
This is useful for learning.
However, a real robot may have many parts:
base_link
base_laser
camera_link
imu_link
left_wheel_link
right_wheel_link
robot_arm_base_link
gripper_link
If you publish every transform manually, the system becomes difficult to maintain.
A better method is:
Describe the robot once in a URDF file.
Then let robot_state_publisher publish the TF frames.
4. What is URDF?
URDF means:
Unified Robot Description Format
URDF is an XML file used to describe a robot.
It can describe:
robot links
robot joints
link shape
link size
link color
joint type
joint origin
parent-child relationship
sensor mounting position
wheel position
For example, instead of manually saying:
base_link → base_laser
x = 0.20
z = 0.15
You can describe this relationship in URDF:
<joint name="base_laser_joint" type="fixed">
<parent link="base_link"/>
<child link="base_laser"/>
<origin xyz="0.20 0.00 0.15" rpy="0 0 0"/>
</joint>
5. Link and joint concept
URDF mainly uses two concepts:
link
joint
5.1 Link
A link is a robot part.
Examples:
base_link
base_laser
camera_link
imu_link
left_wheel_link
right_wheel_link
A link can have visual shape, collision shape, and inertial properties.
In this beginner module, you will mainly use visual shape.
5.2 Joint
A joint connects two links.
A joint defines the relationship between:
parent link
child link
Example:
base_link → base_laser
In URDF:
<joint name="base_laser_joint" type="fixed">
<parent link="base_link"/>
<child link="base_laser"/>
<origin xyz="0.20 0.00 0.15" rpy="0 0 0"/>
</joint>
This means:
base_link is the parent link.
base_laser is the child link.
base_laser is fixed relative to base_link.
6. Important joint types
For this module, you only need two joint types.
| Joint type | Meaning | Example |
| ------------ | ---------------------------------------------------- | ------------------ |
| fixed | The child link does not move relative to parent link | LiDAR, camera, IMU |
| continuous | The child link can rotate continuously | Wheel |
Example fixed joint:
<joint name="camera_joint" type="fixed">
<parent link="base_link"/>
<child link="camera_link"/>
<origin xyz="0.10 0.00 0.40" rpy="0 0 0"/>
</joint>
Example continuous joint:
<joint name="left_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="left_wheel_link"/>
<origin xyz="0.00 0.20 0.05" rpy="1.5708 0 0"/>
<axis xyz="0 0 1"/>
</joint>
7. Target robot model
In this module, you will create a simple AMR model.
The robot contains:
base_link
base_laser
camera_link
imu_link
left_wheel_link
right_wheel_link
The TF tree from URDF will be:
base_link
├── base_laser
├── camera_link
├── imu_link
├── left_wheel_link
└── right_wheel_link
Later, when you combine it with Step 4, the full tree becomes:
odom
└── base_link
├── base_laser
├── camera_link
├── imu_link
├── left_wheel_link
└── right_wheel_link
Later, SLAM or AMCL will add:
map → odom
Then the Nav2-style tree becomes:
map
└── odom
└── base_link
├── base_laser
├── camera_link
├── imu_link
├── left_wheel_link
└── right_wheel_link
8. Install required packages
Open a terminal:
source /opt/ros/jazzy/setup.bash
Install required packages:
sudo apt update
sudo apt install ros-jazzy-robot-state-publisher \
ros-jazzy-joint-state-publisher-gui \
ros-jazzy-xacro \
ros-jazzy-rviz2 \
ros-jazzy-tf2-tools
9. Create a robot description package
Create a workspace if you do not already have one:
mkdir -p ~/ros2_ws/src
cd ~/ros2_ws/src
Create a Python package:
ros2 pkg create --build-type ament_python --license Apache-2.0 amr_description
Go into the package:
cd ~/ros2_ws/src/amr_description
Create folders:
mkdir urdf launch rviz
10. Create a simple AMR URDF file
Create the URDF file:
nano urdf/simple_amr.urdf
Paste the following code:
<?xml version="1.0"?>
<robot name="simple_amr">
<!-- ========================= -->
<!-- Materials -->
<!-- ========================= -->
<material name="blue">
<color rgba="0.0 0.2 0.8 1.0"/>
</material>
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="gray">
<color rgba="0.5 0.5 0.5 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.2 1.0"/>
</material>
<!-- ========================= -->
<!-- Base link -->
<!-- ========================= -->
<link name="base_link">
<visual>
<origin xyz="0 0 0.10" rpy="0 0 0"/>
<geometry>
<box size="0.50 0.35 0.20"/>
</geometry>
<material name="blue"/>
</visual>
</link>
<!-- ========================= -->
<!-- LiDAR link -->
<!-- ========================= -->
<link name="base_laser">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.05" length="0.04"/>
</geometry>
<material name="black"/>
</visual>
</link>
<joint name="base_laser_joint" type="fixed">
<parent link="base_link"/>
<child link="base_laser"/>
<origin xyz="0.20 0.00 0.25" rpy="0 0 0"/>
</joint>
<!-- ========================= -->
<!-- Camera link -->
<!-- ========================= -->
<link name="camera_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.08 0.04 0.04"/>
</geometry>
<material name="green"/>
</visual>
</link>
<joint name="camera_joint" type="fixed">
<parent link="base_link"/>
<child link="camera_link"/>
<origin xyz="0.15 0.00 0.40" rpy="0 0 0"/>
</joint>
<!-- ========================= -->
<!-- IMU link -->
<!-- ========================= -->
<link name="imu_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.05 0.05 0.02"/>
</geometry>
<material name="gray"/>
</visual>
</link>
<joint name="imu_joint" type="fixed">
<parent link="base_link"/>
<child link="imu_link"/>
<origin xyz="0.00 0.00 0.23" rpy="0 0 0"/>
</joint>
<!-- ========================= -->
<!-- Left wheel -->
<!-- ========================= -->
<link name="left_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="0 1.5708 0"/>
<geometry>
<cylinder radius="0.07" length="0.04"/>
</geometry>
<material name="black"/>
</visual>
</link>
<joint name="left_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="left_wheel_link"/>
<origin xyz="0.00 0.20 0.07" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
</joint>
<!-- ========================= -->
<!-- Right wheel -->
<!-- ========================= -->
<link name="right_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="0 1.5708 0"/>
<geometry>
<cylinder radius="0.07" length="0.04"/>
</geometry>
<material name="black"/>
</visual>
</link>
<joint name="right_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="right_wheel_link"/>
<origin xyz="0.00 -0.20 0.07" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
</joint>
</robot>
11. URDF explanation
11.1 Robot name
<robot name="simple_amr">
This names the robot model:
simple_amr
11.2 Main robot body
<link name="base_link">
This is the main body frame of the robot.
In Nav2, base_link is very important because it represents the robot body.
11.3 LiDAR fixed joint
<joint name="base_laser_joint" type="fixed">
<parent link="base_link"/>
<child link="base_laser"/>
<origin xyz="0.20 0.00 0.25" rpy="0 0 0"/>
</joint>
This means:
base_laser is fixed relative to base_link.
base_laser is 0.20 m forward from base_link.
base_laser is 0.25 m above the base_link origin.
11.4 Camera fixed joint
<joint name="camera_joint" type="fixed">
<parent link="base_link"/>
<child link="camera_link"/>
<origin xyz="0.15 0.00 0.40" rpy="0 0 0"/>
</joint>
This means:
camera_link is fixed relative to base_link.
camera_link is 0.15 m forward from base_link.
camera_link is 0.40 m above the base_link origin.
11.5 IMU fixed joint
<joint name="imu_joint" type="fixed">
<parent link="base_link"/>
<child link="imu_link"/>
<origin xyz="0.00 0.00 0.23" rpy="0 0 0"/>
</joint>
This means:
imu_link is fixed relative to base_link.
imu_link is near the center of the robot body.
11.6 Wheel continuous joints
<joint name="left_wheel_joint" type="continuous">
This means the wheel can rotate.
For visualization, you can use joint_state_publisher_gui to change wheel joint values.
12. Create a launch file
Create the launch file:
nano launch/display_amr.launch.py
Paste the following code:
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
package_name = 'amr_description'
urdf_file = os.path.join(
get_package_share_directory(package_name),
'urdf',
'simple_amr.urdf'
)
with open(urdf_file, 'r') as infp:
robot_description = infp.read()
robot_state_publisher_node = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
output='screen',
parameters=[
{'robot_description': robot_description}
]
)
joint_state_publisher_gui_node = Node(
package='joint_state_publisher_gui',
executable='joint_state_publisher_gui',
name='joint_state_publisher_gui'
)
rviz_node = Node(
package='rviz2',
executable='rviz2',
name='rviz2',
output='screen'
)
return LaunchDescription([
robot_state_publisher_node,
joint_state_publisher_gui_node,
rviz_node
])
This launch file starts:
robot_state_publisher
joint_state_publisher_gui
rviz2
13. Modify setup.py
Open setup.py:
nano setup.py
Add these imports at the top:
import os
from glob import glob
Find data_files and modify it like this:
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
(os.path.join('share', package_name, 'launch'), glob('launch/*.py')),
(os.path.join('share', package_name, 'urdf'), glob('urdf/*.urdf')),
(os.path.join('share', package_name, 'rviz'), glob('rviz/*.rviz')),
],
14. Modify package.xml
Open package.xml:
nano package.xml
Add these dependencies before the closing </package> tag:
<exec_depend>joint_state_publisher_gui</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>rviz2</exec_depend>
<exec_depend>tf2_tools</exec_depend>
<exec_depend>xacro</exec_depend>
Save the file.
15. Build the package
Go back to the workspace:
cd ~/ros2_ws
Build:
colcon build --packages-select amr_description
Source the workspace:
source install/setup.bash
16. Run the URDF display launch file
Run:
ros2 launch amr_description display_amr.launch.py
You should see:
RViz2 opens.
joint_state_publisher_gui opens.
robot_state_publisher starts in the terminal.
17. Configure RViz2
In RViz2:
1. Set Fixed Frame to base_link.
2. Click Add.
3. Add RobotModel.
4. Add TF.
For RobotModel:
Description Topic or Parameter should use robot_description.
You should see the AMR model.
You should also see TF frames:
base_link
base_laser
camera_link
imu_link
left_wheel_link
right_wheel_link
18. Test wheel joints
In the joint_state_publisher_gui window, move the sliders for:
left_wheel_joint
right_wheel_joint
You should observe:
The wheel frames rotate.
The RobotModel updates in RViz2.
The fixed sensor frames should not move relative to base_link.
19. Check TF frames using command line
Open another terminal:
source ~/ros2_ws/install/setup.bash
Check the TF tree:
ros2 run tf2_tools view_frames
Open the generated file:
xdg-open frames.pdf
Expected TF tree:
base_link
├── base_laser
├── camera_link
├── imu_link
├── left_wheel_link
└── right_wheel_link
Check one transform:
ros2 run tf2_ros tf2_echo base_link base_laser
Expected translation:
x = 0.20
y = 0.00
z = 0.25
Check camera:
ros2 run tf2_ros tf2_echo base_link camera_link
Expected translation:
x = 0.15
y = 0.00
z = 0.40
Check IMU:
ros2 run tf2_ros tf2_echo base_link imu_link
Expected translation:
x = 0.00
y = 0.00
z = 0.23
20. Combine Step 4 and Step 5
Now combine the dynamic odometry frame from Step 4 with the URDF model from Step 5.
Terminal 1: Run URDF model
source ~/ros2_ws/install/setup.bash
ros2 launch amr_description display_amr.launch.py
Terminal 2: Run fake odometry TF broadcaster
source ~/ros2_ws/install/setup.bash
ros2 run amr_tf2_dynamic fake_odom_tf_broadcaster
Now generate the TF tree:
ros2 run tf2_tools view_frames
xdg-open frames.pdf
Expected result:
odom
└── base_link
├── base_laser
├── camera_link
├── imu_link
├── left_wheel_link
└── right_wheel_link
This is a strong result.
You now have:
Dynamic odometry frame from Python.
Robot structure and sensor frames from URDF.
21. Why this is better than manual static transform publishers
In Step 3, you used several static transform publishers:
base_link → base_laser
base_link → camera_link
base_link → imu_link
This is fine for learning.
But in a real robot, URDF is better because:
The robot structure is stored in one file.
The visual model can be shown in RViz2.
The TF tree is easier to maintain.
Sensor positions are easier to check.
Wheel and joint frames can be included.
Robot arms and grippers can be added later.
For your AMR course, this is important because students can see the relationship between:
mechanical design
sensor mounting
TF frames
Nav2 navigation
22. Connection to Nav2
Nav2 needs a correct TF tree.
After Step 5, you can already build this:
odom
└── base_link
├── base_laser
├── camera_link
└── imu_link
This means:
Nav2 can know where the robot body is in odom.
Nav2 can know where the LiDAR is relative to the robot body.
Nav2 can know where the camera is relative to the robot body.
Nav2 can know where the IMU is relative to the robot body.
Later, SLAM or AMCL will add:
map → odom
Then the full Nav2 TF tree becomes:
map
└── odom
└── base_link
├── base_laser
├── camera_link
└── imu_link
Important:
robot_state_publisher should publish the robot body and sensor frames.
Odometry should publish odom → base_link.
SLAM or AMCL should publish map → odom.
You should avoid duplicate TF publishers.
23. Common problems and solutions
Problem 1: RViz2 shows nothing
Possible reasons:
Fixed Frame is wrong.
RobotModel display is not added.
TF display is not added.
robot_state_publisher is not running.
Solution:
Set Fixed Frame to base_link.
Add RobotModel.
Add TF.
Check terminal output.
Problem 2: RobotModel has error
Possible reasons:
URDF file has XML syntax error.
The robot_description parameter is not loaded.
The launch file cannot find the URDF file.
Check:
ls ~/ros2_ws/src/amr_description/urdf
Rebuild:
cd ~/ros2_ws
colcon build --packages-select amr_description
source install/setup.bash
Problem 3: ros2 launch cannot find the package
Possible reason:
The workspace has not been sourced.
Solution:
source ~/ros2_ws/install/setup.bash
Problem 4: Launch file cannot find the URDF
Possible reasons:
The URDF file was not installed.
setup.py data_files does not include the urdf folder.
You forgot to rebuild after modifying setup.py.
Solution:
Check setup.py.
Rebuild the package.
Source the workspace again.
Commands:
cd ~/ros2_ws
colcon build --packages-select amr_description
source install/setup.bash
Problem 5: TF tree shows only base_link but no child frames
Possible reasons:
The URDF joints are missing.
The child links are not connected.
The URDF file was not updated in the installed workspace.
Solution:
Check the parent and child link names.
Make sure every child link has a joint.
Rebuild and source again.
Problem 6: Duplicate TF publishers
Problem example:
Step 3 static transform publisher publishes base_link → base_laser.
Step 5 robot_state_publisher also publishes base_link → base_laser.
This creates duplicate TF sources.
Better:
When using URDF + robot_state_publisher, do not also publish the same static transform manually.
24. Practice assignment
Assignment title
Create and Visualize a Simple AMR URDF Model
Task 1: Create the package
Create:
amr_description
The package should include:
urdf/simple_amr.urdf
launch/display_amr.launch.py
Task 2: Create the AMR model
Your AMR should include:
base_link
base_laser
camera_link
imu_link
left_wheel_link
right_wheel_link
Task 3: Run the launch file
Run:
ros2 launch amr_description display_amr.launch.py
Submit a screenshot of RViz2.
Task 4: Generate the TF tree
Run:
ros2 run tf2_tools view_frames
Submit the generated TF tree screenshot.
Task 5: Check sensor transforms
Run:
ros2 run tf2_ros tf2_echo base_link base_laser
Run:
ros2 run tf2_ros tf2_echo base_link camera_link
Run:
ros2 run tf2_ros tf2_echo base_link imu_link
Submit screenshots.
Task 6: Combine with Step 4
Run the URDF model and the fake odometry node together:
ros2 launch amr_description display_amr.launch.py
ros2 run amr_tf2_dynamic fake_odom_tf_broadcaster
Generate the TF tree.
Expected result:
odom
└── base_link
├── base_laser
├── camera_link
├── imu_link
├── left_wheel_link
└── right_wheel_link
Submit the screenshot.
25. Mini quiz
- What does URDF mean?
- What is a link in URDF?
- What is a joint in URDF?
- What is the parent link in
base_link → base_laser? - What is the child link in
base_link → base_laser? - What does
robot_state_publisherdo? - What does
joint_state_publisher_guido? - Why is URDF better than many manual static transform publishers?
- In Nav2, should URDF publish
odom → base_link? - In Nav2, who should usually publish
map → odom?
26. Key summary
In this module, you learned how to describe a robot using URDF.
You created:
base_link
base_laser
camera_link
imu_link
left_wheel_link
right_wheel_link
You used:
robot_state_publisher
joint_state_publisher_gui
RViz2
view_frames
tf2_echo
The main idea is:
URDF describes the robot structure.
robot_state_publisher converts the URDF structure into TF frames.
RViz2 visualizes the robot model and TF tree.
After combining Step 4 and Step 5, you can build:
odom
└── base_link
├── base_laser
├── camera_link
├── imu_link
├── left_wheel_link
└── right_wheel_link
This is a major step toward Nav2.
In the next module, you will learn:
SLAM mapping
SLAM will help you build a map and later provide the relationship between:
map → odom