Position in the full course
This is the third 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 2, you learned the TF2 frame concept.
In Step 3, you will publish fixed sensor frames, such as:
base_link → base_laser
base_link → camera_link
base_link → imu_link
These transforms describe where sensors are mounted on the robot.
1. Learning objectives
After this module, you should be able to:
- Explain what a static transform is.
- Explain why sensor frames are usually static.
- Publish a static transform from the command line.
- Publish several static sensor frames using a Python launch file.
- Use
tf2_echoto check a static transform. - Use
view_framesto generate a TF tree. - Use RViz2 to visualize static frames.
- Understand how static sensor frames support Nav2.
- Understand when to use
static_transform_publisherand when to use URDF.
2. Suggested teaching duration
Suggested duration: 2 hours
| Time | Activity | | ----------- | ---------------------------------------------------- | | 0–15 min | Review TF2 frame concept | | 15–30 min | Explain static sensor frames | | 30–50 min | Publish one static transform from command line | | 50–75 min | Publish multiple static transforms using launch file | | 75–95 min | Visualize frames in RViz2 | | 95–110 min | Optional Python static broadcaster node | | 110–120 min | Summary and homework |
3. What is a static transform?
A static transform describes a frame relationship that does not change over time.
Example:
base_link → base_laser
This means the LiDAR is mounted at a fixed position relative to the robot body.
If the LiDAR is fixed on the robot chassis, the transform does not change while the robot moves.
For example:
The robot moves.
The LiDAR moves with the robot.
But the LiDAR position relative to the robot body is fixed.
Therefore:
base_link → base_laser
is static.
4. Static frames on a mobile robot
For an AMR, you may have these frames:
base_link
base_laser
camera_link
imu_link
A simple TF tree may look like this:
base_link
├── base_laser
├── camera_link
└── imu_link
Meaning:
base_laser is fixed relative to base_link.
camera_link is fixed relative to base_link.
imu_link is fixed relative to base_link.
Later, this tree will be connected to the full Nav2 tree:
map
└── odom
└── base_link
├── base_laser
├── camera_link
└── imu_link
5. Coordinate convention reminder
For a mobile robot, a common convention is:
x-axis: forward
y-axis: left
z-axis: upward
So if the LiDAR is mounted 20 cm in front of the robot center and 15 cm above the robot base, you can write:
x = 0.20
y = 0.00
z = 0.15
This means:
The LiDAR is 0.20 m forward from base_link.
The LiDAR is not shifted left or right.
The LiDAR is 0.15 m above base_link.
Important:
TF2 uses meters, not centimeters.
So:
20 cm = 0.20 m
15 cm = 0.15 m
6. Practice 1: Publish one static transform from command line
First, source ROS 2:
source /opt/ros/jazzy/setup.bash
Publish a static transform from base_link to base_laser:
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 means:
parent frame: base_link
child frame: base_laser
translation: x = 0.20 m, y = 0.00 m, z = 0.15 m
rotation: no rotation
Keep this terminal running.
7. Practice 2: Check the transform using tf2_echo
Open a new terminal:
source /opt/ros/jazzy/setup.bash
Run:
ros2 run tf2_ros tf2_echo base_link base_laser
Expected output should be similar to:
At time 0.0
- Translation: [0.200, 0.000, 0.150]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
Explanation:
base_link base_laser
means:
Where is base_laser relative to base_link?
You should see:
base_laser is 0.20 m forward and 0.15 m upward from base_link.
8. Practice 3: Check /tf_static topic
Run:
ros2 topic echo /tf_static
You should see the static transform message.
Important:
/tf contains dynamic transforms.
/tf_static contains static transforms.
In this lesson, your sensor frames are published to:
/tf_static
9. Practice 4: Generate the TF tree
Open another terminal:
source /opt/ros/jazzy/setup.bash
Run:
ros2 run tf2_tools view_frames
This generates:
frames.pdf
Open it:
xdg-open frames.pdf
You should see:
base_link
└── base_laser
Question:
Which frame is the parent?
Which frame is the child?
Expected answer:
base_link is the parent frame.
base_laser is the child frame.
10. Practice 5: Visualize the static frame in RViz2
Open RViz2:
rviz2
In RViz2:
1. Set Fixed Frame to base_link.
2. Click Add.
3. Choose TF.
4. Click OK.
You should see:
base_link
base_laser
If the frames are too small, you can increase the marker scale in the TF display.
11. Practice 6: Add camera and IMU frames
Stop the previous static_transform_publisher terminal with:
Ctrl + C
Now publish three static sensor frames in three different terminals.
Terminal 1: LiDAR frame
source /opt/ros/jazzy/setup.bash
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
Terminal 2: Camera frame
source /opt/ros/jazzy/setup.bash
ros2 run tf2_ros static_transform_publisher \
--x 0.10 --y 0.00 --z 0.40 \
--roll 0 --pitch 0 --yaw 0 \
--frame-id base_link \
--child-frame-id camera_link
Terminal 3: IMU frame
source /opt/ros/jazzy/setup.bash
ros2 run tf2_ros static_transform_publisher \
--x 0.00 --y 0.00 --z 0.10 \
--roll 0 --pitch 0 --yaw 0 \
--frame-id base_link \
--child-frame-id imu_link
Now check the TF tree:
ros2 run tf2_tools view_frames
xdg-open frames.pdf
You should see:
base_link
├── base_laser
├── camera_link
└── imu_link
12. Why using many terminals is inconvenient
Publishing one frame from one terminal is okay for learning.
But real robots have many frames.
For example:
base_link → base_laser
base_link → camera_link
base_link → imu_link
base_link → left_wheel
base_link → right_wheel
base_link → robot_arm_base
Starting each transform manually is not convenient.
So you should use a launch file.
13. Practice 7: Create a package for static sensor frames
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_tf2_static
Go into the package:
cd ~/ros2_ws/src/amr_tf2_static
Create a launch folder:
mkdir launch
14. Practice 8: Create a Python launch file
Create the launch file:
nano launch/static_sensor_frames.launch.py
Paste this code:
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
base_laser_tf = Node(
package='tf2_ros',
executable='static_transform_publisher',
name='base_laser_static_tf',
arguments=[
'--x', '0.20',
'--y', '0.00',
'--z', '0.15',
'--roll', '0',
'--pitch', '0',
'--yaw', '0',
'--frame-id', 'base_link',
'--child-frame-id', 'base_laser'
]
)
camera_tf = Node(
package='tf2_ros',
executable='static_transform_publisher',
name='camera_static_tf',
arguments=[
'--x', '0.10',
'--y', '0.00',
'--z', '0.40',
'--roll', '0',
'--pitch', '0',
'--yaw', '0',
'--frame-id', 'base_link',
'--child-frame-id', 'camera_link'
]
)
imu_tf = Node(
package='tf2_ros',
executable='static_transform_publisher',
name='imu_static_tf',
arguments=[
'--x', '0.00',
'--y', '0.00',
'--z', '0.10',
'--roll', '0',
'--pitch', '0',
'--yaw', '0',
'--frame-id', 'base_link',
'--child-frame-id', 'imu_link'
]
)
return LaunchDescription([
base_laser_tf,
camera_tf,
imu_tf
])
This launch file starts three static transform publishers:
base_link → base_laser
base_link → camera_link
base_link → imu_link
15. Practice 9: Modify setup.py to install the launch file
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')),
],
Save the file.
16. Practice 10: Build and run the launch file
Go back to the workspace:
cd ~/ros2_ws
Build:
colcon build --packages-select amr_tf2_static
Source the workspace:
source install/setup.bash
Run the launch file:
ros2 launch amr_tf2_static static_sensor_frames.launch.py
Now the three static sensor frames are published from one command.
17. Practice 11: Verify the frames
Open a new terminal:
source ~/ros2_ws/install/setup.bash
Check the LiDAR transform:
ros2 run tf2_ros tf2_echo base_link base_laser
Check the camera transform:
ros2 run tf2_ros tf2_echo base_link camera_link
Check the IMU transform:
ros2 run tf2_ros tf2_echo base_link imu_link
Generate the TF tree:
ros2 run tf2_tools view_frames
xdg-open frames.pdf
Expected TF tree:
base_link
├── base_laser
├── camera_link
└── imu_link
18. Practice 12: Visualize all frames in RViz2
Run:
rviz2
In RViz2:
1. Set Fixed Frame to base_link.
2. Add TF display.
3. Observe base_laser, camera_link, and imu_link.
You should see three child frames attached to base_link.
19. Optional: Write your own Python static broadcaster node
In real development, using static_transform_publisher in a launch file is usually better.
However, writing your own Python node helps you understand how TF2 works.
Create a Python file:
cd ~/ros2_ws/src/amr_tf2_static/amr_tf2_static
nano static_sensor_broadcaster.py
Paste this code:
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import TransformStamped
from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster
class StaticSensorBroadcaster(Node):
def __init__(self):
super().__init__('static_sensor_broadcaster')
self.static_broadcaster = StaticTransformBroadcaster(self)
transforms = [
self.create_transform(
'base_link', 'base_laser',
0.20, 0.00, 0.15,
0.0, 0.0, 0.0, 1.0
),
self.create_transform(
'base_link', 'camera_link',
0.10, 0.00, 0.40,
0.0, 0.0, 0.0, 1.0
),
self.create_transform(
'base_link', 'imu_link',
0.00, 0.00, 0.10,
0.0, 0.0, 0.0, 1.0
)
]
self.static_broadcaster.sendTransform(transforms)
self.get_logger().info('Static sensor transforms have been published.')
def create_transform(self, parent_frame, child_frame,
x, y, z,
qx, qy, qz, qw):
transform = TransformStamped()
transform.header.stamp = self.get_clock().now().to_msg()
transform.header.frame_id = parent_frame
transform.child_frame_id = child_frame
transform.transform.translation.x = x
transform.transform.translation.y = y
transform.transform.translation.z = z
transform.transform.rotation.x = qx
transform.transform.rotation.y = qy
transform.transform.rotation.z = qz
transform.transform.rotation.w = qw
return transform
def main(args=None):
rclpy.init(args=args)
node = StaticSensorBroadcaster()
try:
rclpy.spin(node)
except KeyboardInterrupt:
pass
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
This node publishes three static transforms:
base_link → base_laser
base_link → camera_link
base_link → imu_link
20. Optional: Modify package.xml
Open package.xml:
cd ~/ros2_ws/src/amr_tf2_static
nano package.xml
Add these dependencies before the closing </package> tag:
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>rclpy</exec_depend>
<exec_depend>tf2_ros_py</exec_depend>
21. Optional: Modify setup.py for the Python node
Open setup.py:
nano setup.py
Find entry_points and modify it:
entry_points={
'console_scripts': [
'static_sensor_broadcaster = amr_tf2_static.static_sensor_broadcaster:main',
],
},
Build again:
cd ~/ros2_ws
colcon build --packages-select amr_tf2_static
source install/setup.bash
Run the Python static broadcaster:
ros2 run amr_tf2_static static_sensor_broadcaster
Then verify:
ros2 run tf2_tools view_frames
xdg-open frames.pdf
22. Which method should you use?
There are three common ways to publish static frames.
| Method | Good for | Recommendation |
| ---------------------------------------------------- | -------------------------------------- | ----------------------------- |
| Command-line static_transform_publisher | Quick testing | Good for learning |
| Python launch file with static_transform_publisher | Small projects and classroom practice | Good for this course |
| URDF + robot_state_publisher | Real robot with many links and sensors | Best for larger robot systems |
For this course:
Use static_transform_publisher in a Python launch file.
For a real AMR:
Use URDF + robot_state_publisher.
You will learn URDF and robot_state_publisher in Step 5.
23. Connection to Nav2
Nav2 needs sensor data to be connected to the robot body frame.
For example, LiDAR scan data is usually measured in the LiDAR frame:
base_laser
But Nav2 needs to understand this sensor data relative to the robot body:
base_link
Therefore, you need:
base_link → base_laser
If this transform is missing, Nav2 may not be able to correctly use LiDAR data for costmaps.
A typical Nav2 TF tree is:
map
└── odom
└── base_link
├── base_laser
├── camera_link
└── imu_link
In this step, you only build the lower part:
base_link
├── base_laser
├── camera_link
└── imu_link
In the next step, you will add:
odom → base_link
24. Common problems and solutions
Problem 1: tf2_echo says frame does not exist
Example error:
Invalid frame ID "base_laser" passed to canTransform argument source_frame - frame does not exist
Possible reasons:
The static transform publisher is not running.
The frame name is typed incorrectly.
The workspace has not been sourced.
The launch file did not start correctly.
Check:
ros2 topic echo /tf_static
ros2 run tf2_tools view_frames
Problem 2: RViz2 shows no TF frames
Possible reasons:
Fixed Frame is wrong.
TF display has not been added.
The static transform publisher is not running.
Solution:
Set Fixed Frame to base_link.
Add TF display.
Check /tf_static.
Problem 3: Transform direction is wrong
Wrong:
base_laser → base_link
Correct for this lesson:
base_link → base_laser
Reason:
base_link should be the parent frame.
base_laser should be the child frame.
Problem 4: Units are wrong
Wrong:
x = 20
z = 15
This means:
20 meters forward
15 meters upward
Correct:
x = 0.20
z = 0.15
This means:
20 centimeters forward
15 centimeters upward
Problem 5: Duplicate child frame
Wrong idea:
Two different publishers both publish base_link → base_laser.
Problem:
TF may become confusing because the same child frame is published by multiple sources.
Better:
Only one node should publish one specific parent-child static transform.
25. Practice assignment
Assignment title
Build Static Sensor Frames for an AMR
Task 1: Create an AMR static TF launch file
Create a launch file that publishes these frames:
base_link → base_laser
base_link → camera_link
base_link → imu_link
Use these values:
| Parent frame | Child frame | x | y | z | roll | pitch | yaw |
| ------------ | ------------- | ---- | ---- | ---- | ---- | ----- | --- |
| base_link | base_laser | 0.20 | 0.00 | 0.15 | 0 | 0 | 0 |
| base_link | camera_link | 0.10 | 0.00 | 0.40 | 0 | 0 | 0 |
| base_link | imu_link | 0.00 | 0.00 | 0.10 | 0 | 0 | 0 |
Task 2: Verify using tf2_echo
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 3: Generate TF tree
Run:
ros2 run tf2_tools view_frames
Submit the generated TF tree screenshot.
Task 4: Visualize in RViz2
Open RViz2:
rviz2
Set:
Fixed Frame = base_link
Add:
TF display
Submit a screenshot.
Task 5: Explain the result
Write a short explanation:
The parent frame is:
The child sensor frames are:
The LiDAR is located:
The camera is located:
The IMU is located:
These transforms are static because:
26. Mini quiz
- What is a static transform?
- Why is
base_link → base_laserusually static? - What topic is used for static transforms?
- What command can publish a static transform from the command line?
- What command can check the transform between two frames?
- What command can generate a TF tree PDF?
- In
base_link → camera_link, which frame is the parent? - In
base_link → camera_link, which frame is the child? - Why should you use meters instead of centimeters in TF2?
- For a real robot, why is URDF usually better than many manual static transform publishers?
27. Key summary
In this module, you learned how to publish static sensor frames.
A static transform describes a fixed relationship between two frames.
For example:
base_link → base_laser
means the LiDAR is fixed relative to the robot body.
You practiced:
static_transform_publisher
tf2_echo
view_frames
RViz2 TF display
Python launch file
You built this TF tree:
base_link
├── base_laser
├── camera_link
└── imu_link
This is the sensor-frame part of a Nav2 TF tree.
In the next module, you will learn how to publish a dynamic transform:
odom → base_link
This transform changes over time because the robot moves.