Position in the full course
This is the fourth 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 published static sensor frames:
base_link → base_laser
base_link → camera_link
base_link → imu_link
In Step 4, you will publish a dynamic transform:
odom → base_link
This transform changes over time because the robot moves.
1. Learning objectives
After this module, you should be able to:
- Explain what a dynamic transform is.
- Explain why
odom → base_linkis dynamic. - Explain the difference between
/odomand/tf. - Write a Python node that publishes
odom → base_link. - Write a Python node that publishes
nav_msgs/msg/Odometry. - Use
tf2_echoto check the moving robot frame. - Use
view_framesto generate the TF tree. - Use RViz2 to visualize a moving
base_link. - Connect dynamic odometry TF to Nav2.
2. Suggested teaching duration
Suggested duration: 2 hours
| Time | Activity |
| ----------- | ----------------------------------------------- |
| 0–15 min | Review static sensor frames |
| 15–30 min | Explain dynamic transform |
| 30–45 min | Explain odom, base_link, /odom, and /tf |
| 45–80 min | Create Python dynamic odometry broadcaster |
| 80–95 min | Build and run the node |
| 95–110 min | Verify using TF2 tools and RViz2 |
| 110–120 min | Summary and homework |
3. What is a dynamic transform?
A dynamic transform is a transform that changes over time.
In Step 3, you published static transforms such as:
base_link → base_laser
base_link → camera_link
base_link → imu_link
These are static because the sensors are fixed on the robot body.
However, when the robot moves, the robot body changes its position in the odometry frame.
Therefore:
odom → base_link
is dynamic.
The transform changes because:
The robot moves forward.
The robot turns.
The robot position changes.
The robot orientation changes.
4. Meaning of odom → base_link
The frame base_link is attached to the robot body.
The frame odom is the odometry reference frame.
The transform:
odom → base_link
means:
Where is the robot body relative to the odometry frame?
For example:
x = 1.0 m
y = 0.5 m
yaw = 30 degrees
This means the robot is located at:
1.0 m forward in the odom frame
0.5 m left in the odom frame
rotated 30 degrees
5. Difference between /odom and /tf
This is very important.
/odom
/odom is usually a topic.
It publishes an odometry message:
nav_msgs/msg/Odometry
The odometry message contains:
position
orientation
linear velocity
angular velocity
covariance
/tf
/tf is also a topic.
It carries dynamic transform information.
For this module, /tf carries:
odom → base_link
Simple comparison
| Item | Meaning |
| ------------------ | --------------------------------- |
| /odom | Robot odometry data |
| /tf | Coordinate transform relationship |
| odom | Coordinate frame |
| base_link | Robot body frame |
| odom → base_link | Robot pose in odometry frame |
Important:
For Nav2, publishing only
/odomis not enough. You also need theodom → base_linkTF transform.
6. Target TF tree in this module
In Step 4 alone, you will build:
odom
└── base_link
If you also run the Step 3 static sensor frame launch file, you will get:
odom
└── base_link
├── base_laser
├── camera_link
└── imu_link
This is already close to a Nav2 TF tree.
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
7. Create a package for dynamic odometry TF
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_dynamic
Go into the package:
cd ~/ros2_ws/src/amr_tf2_dynamic
8. Modify package.xml
Open package.xml:
nano package.xml
Add these dependencies before the closing </package> tag:
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>nav_msgs</exec_depend>
<exec_depend>rclpy</exec_depend>
<exec_depend>tf2_ros_py</exec_depend>
Save the file.
9. Create the dynamic odometry broadcaster node
Go to the Python module folder:
cd ~/ros2_ws/src/amr_tf2_dynamic/amr_tf2_dynamic
Create a Python file:
nano fake_odom_tf_broadcaster.py
Paste the following code:
import math
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import TransformStamped
from nav_msgs.msg import Odometry
from tf2_ros import TransformBroadcaster
def quaternion_from_yaw(yaw):
"""
Convert a yaw angle into a quaternion.
For a 2D mobile robot:
roll = 0
pitch = 0
yaw = heading angle
"""
qx = 0.0
qy = 0.0
qz = math.sin(yaw / 2.0)
qw = math.cos(yaw / 2.0)
return qx, qy, qz, qw
class FakeOdomTfBroadcaster(Node):
def __init__(self):
super().__init__('fake_odom_tf_broadcaster')
self.tf_broadcaster = TransformBroadcaster(self)
self.odom_publisher = self.create_publisher(
Odometry,
'odom',
10
)
self.timer_period = 0.05
self.timer = self.create_timer(
self.timer_period,
self.timer_callback
)
self.x = 0.0
self.y = 0.0
self.yaw = 0.0
self.linear_velocity = 0.20
self.angular_velocity = 0.30
self.get_logger().info('Fake odom TF broadcaster has started.')
def timer_callback(self):
dt = self.timer_period
self.x += self.linear_velocity * math.cos(self.yaw) * dt
self.y += self.linear_velocity * math.sin(self.yaw) * dt
self.yaw += self.angular_velocity * dt
qx, qy, qz, qw = quaternion_from_yaw(self.yaw)
now = self.get_clock().now().to_msg()
# -----------------------------
# Publish TF: odom → base_link
# -----------------------------
transform = TransformStamped()
transform.header.stamp = now
transform.header.frame_id = 'odom'
transform.child_frame_id = 'base_link'
transform.transform.translation.x = self.x
transform.transform.translation.y = self.y
transform.transform.translation.z = 0.0
transform.transform.rotation.x = qx
transform.transform.rotation.y = qy
transform.transform.rotation.z = qz
transform.transform.rotation.w = qw
self.tf_broadcaster.sendTransform(transform)
# -----------------------------
# Publish Odometry topic: /odom
# -----------------------------
odom_msg = Odometry()
odom_msg.header.stamp = now
odom_msg.header.frame_id = 'odom'
odom_msg.child_frame_id = 'base_link'
odom_msg.pose.pose.position.x = self.x
odom_msg.pose.pose.position.y = self.y
odom_msg.pose.pose.position.z = 0.0
odom_msg.pose.pose.orientation.x = qx
odom_msg.pose.pose.orientation.y = qy
odom_msg.pose.pose.orientation.z = qz
odom_msg.pose.pose.orientation.w = qw
odom_msg.twist.twist.linear.x = self.linear_velocity
odom_msg.twist.twist.linear.y = 0.0
odom_msg.twist.twist.linear.z = 0.0
odom_msg.twist.twist.angular.x = 0.0
odom_msg.twist.twist.angular.y = 0.0
odom_msg.twist.twist.angular.z = self.angular_velocity
self.odom_publisher.publish(odom_msg)
self.get_logger().info(
'Publishing odom → base_link: x=%.2f, y=%.2f, yaw=%.2f'
% (self.x, self.y, self.yaw)
)
def main(args=None):
rclpy.init(args=args)
node = FakeOdomTfBroadcaster()
try:
rclpy.spin(node)
except KeyboardInterrupt:
pass
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
10. Code explanation
10.1 Node name
super().__init__('fake_odom_tf_broadcaster')
This creates a ROS 2 node named:
fake_odom_tf_broadcaster
10.2 TF broadcaster
self.tf_broadcaster = TransformBroadcaster(self)
This object publishes dynamic transforms to TF2.
In this module, it publishes:
odom → base_link
10.3 Odometry publisher
self.odom_publisher = self.create_publisher(
Odometry,
'odom',
10
)
This creates a publisher for the topic:
odom
The message type is:
nav_msgs/msg/Odometry
10.4 Robot motion model
self.x += self.linear_velocity * math.cos(self.yaw) * dt
self.y += self.linear_velocity * math.sin(self.yaw) * dt
self.yaw += self.angular_velocity * dt
This creates simple fake robot motion.
The robot moves forward and slowly turns.
This is not a real odometry algorithm.
It is only for learning TF2.
10.5 Quaternion conversion
qz = math.sin(yaw / 2.0)
qw = math.cos(yaw / 2.0)
For a 2D mobile robot:
roll = 0
pitch = 0
yaw = heading angle
So only qz and qw change.
11. Modify setup.py
Open setup.py:
cd ~/ros2_ws/src/amr_tf2_dynamic
nano setup.py
Find entry_points and modify it:
entry_points={
'console_scripts': [
'fake_odom_tf_broadcaster = amr_tf2_dynamic.fake_odom_tf_broadcaster:main',
],
},
Save the file.
12. Build the package
Go back to the workspace:
cd ~/ros2_ws
Build:
colcon build --packages-select amr_tf2_dynamic
Source the workspace:
source install/setup.bash
13. Run the dynamic odometry broadcaster
Run:
ros2 run amr_tf2_dynamic fake_odom_tf_broadcaster
You should see output similar to:
Publishing odom → base_link: x=0.01, y=0.00, yaw=0.01
Publishing odom → base_link: x=0.02, y=0.00, yaw=0.03
Publishing odom → base_link: x=0.03, y=0.00, yaw=0.04
This means the node is publishing a changing robot pose.
14. Verify the /odom topic
Open another terminal:
source ~/ros2_ws/install/setup.bash
Check the topic list:
ros2 topic list
You should see:
/odom
/tf
Check the odometry message type:
ros2 topic type /odom
Expected result:
nav_msgs/msg/Odometry
Echo the odometry topic:
ros2 topic echo /odom
You should see changing position and orientation values.
15. Verify the TF transform using tf2_echo
Run:
ros2 run tf2_ros tf2_echo odom base_link
This asks:
Where is base_link relative to odom?
You should see changing values:
Translation: [x, y, 0.000]
Rotation: in Quaternion [0.000, 0.000, qz, qw]
The values should change because the robot is moving.
16. Generate the TF tree
Run:
ros2 run tf2_tools view_frames
Open the PDF:
xdg-open frames.pdf
You should see:
odom
└── base_link
This means your dynamic transform is working.
17. Visualize the moving frame in RViz2
Open RViz2:
rviz2
In RViz2:
1. Set Fixed Frame to odom.
2. Click Add.
3. Choose TF.
4. Click OK.
You should see:
base_link moving relative to odom.
You can also add an Odometry display:
1. Click Add.
2. Choose Odometry.
3. Set Topic to /odom.
This helps you visualize the odometry trajectory.
18. Combine Step 3 and Step 4
If you completed Step 3, open another terminal and run:
source ~/ros2_ws/install/setup.bash
ros2 launch amr_tf2_static static_sensor_frames.launch.py
Keep the Step 4 dynamic odometry node running.
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
This is an important result.
You now have:
A dynamic robot body frame.
Static sensor frames attached to the robot body.
19. Why this is important for Nav2
Nav2 needs to know where the robot is moving.
The transform:
odom → base_link
tells Nav2 the robot pose according to odometry.
Nav2 also needs sensor frames:
base_link → base_laser
base_link → camera_link
base_link → imu_link
These tell Nav2 where sensor data comes from.
A minimal Nav2-related TF structure is:
odom
└── base_link
└── base_laser
For localization and global navigation, you also need:
map → odom
This will be added later by SLAM or AMCL.
20. Important note for real robots
The node in this module publishes fake odometry.
It is useful for learning.
For a real robot, odom → base_link should come from a real odometry source, such as:
wheel encoder odometry
IMU + wheel encoder fusion
visual odometry
robot_localization package
Gazebo simulation plugin
ros2_control diff drive controller
In a real Nav2 system, do not use fake odometry unless you are only testing TF visualization.
21. Common problems and solutions
Problem 1: tf2_echo says frame does not exist
Example:
Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist
Possible reasons:
The fake odometry node is not running.
The workspace has not been sourced.
The frame name is typed incorrectly.
Check:
ros2 topic list
ros2 topic echo /tf
Problem 2: /odom exists but TF does not exist
Possible reason:
You published nav_msgs/msg/Odometry but did not publish TransformStamped to TF2.
Remember:
Publishing /odom and publishing odom → base_link TF are related but not the same thing.
Problem 3: TF exists but /odom does not exist
Possible reason:
You published TransformStamped but did not publish nav_msgs/msg/Odometry.
For Nav2, you usually need both.
Problem 4: RViz2 shows no frames
Possible reasons:
Fixed Frame is wrong.
TF display has not been added.
The dynamic broadcaster node is not running.
Solution:
Set Fixed Frame to odom.
Add TF display.
Check /tf.
Problem 5: base_link does not move in RViz2
Possible reasons:
The node is not updating x, y, or yaw.
The timer is not running.
The transform timestamp is not updating.
Check the terminal output:
x, y, and yaw should change over time.
Problem 6: You accidentally publish duplicate odom → base_link
Problem:
Two nodes publish the same odom → base_link transform.
This can happen if you run:
fake odom node
real robot odometry node
Gazebo odometry plugin
robot_localization
at the same time.
Better:
Only one source should publish odom → base_link.
22. Practice assignment
Assignment title
Publish a Dynamic Odometry Frame for an AMR
Task 1: Run the fake odometry broadcaster
Run:
ros2 run amr_tf2_dynamic fake_odom_tf_broadcaster
Submit a screenshot of the terminal output.
Task 2: Check /odom
Run:
ros2 topic echo /odom
Submit a screenshot showing changing position values.
Task 3: Check odom → base_link
Run:
ros2 run tf2_ros tf2_echo odom base_link
Submit a screenshot showing changing transform values.
Task 4: Generate the TF tree
Run:
ros2 run tf2_tools view_frames
Submit the generated TF tree screenshot.
Task 5: Visualize in RViz2
Run:
rviz2
Set:
Fixed Frame = odom
Add:
TF display
Odometry display
Submit a screenshot.
Task 6: Combine with Step 3
Run both:
ros2 launch amr_tf2_static static_sensor_frames.launch.py
and:
ros2 run amr_tf2_dynamic fake_odom_tf_broadcaster
Generate the TF tree again.
Expected result:
odom
└── base_link
├── base_laser
├── camera_link
└── imu_link
Submit the screenshot.
23. Mini quiz
- What is a dynamic transform?
- Why is
odom → base_linkdynamic? - What does
/odompublish? - What does
/tfpublish? - Is
/odomthe same asodomframe? - What command checks the transform from
odomtobase_link? - What RViz2 Fixed Frame should you use in this module?
- Why do you need both
/odomandodom → base_linkfor Nav2? - What should publish
odom → base_linkon a real robot? - Why should you avoid duplicate
odom → base_linkpublishers?
24. Key summary
In this module, you learned how to publish a dynamic odometry frame.
You created:
odom → base_link
You also published:
topic: /odom
message type: nav_msgs/msg/Odometry
You learned that:
odom is a coordinate frame.
base_link is the robot body frame.
/odom is an odometry topic.
/tf carries the dynamic transform.
After combining Step 3 and Step 4, you can build:
odom
└── base_link
├── base_laser
├── camera_link
└── imu_link
This is a major part of the Nav2 TF structure.
In the next module, you will learn:
URDF + robot_state_publisher
This will help you describe the robot structure in a cleaner and more realistic way.