02-tf2-time-qos.mdEstimated time: 60 minutes
Prerequisite: 02-tf2-time-qos.md
Self-assessment guide: Work Section A from memory. If you can correctly answer A2 and A3
without hints, you can diagnose ExtrapolationException errors in field bags without reading
source code.
TF2 lookup failures are responsible for a disproportionate share of navigation stack failures
that are hard to diagnose because the error message (ExtrapolationException) is often printed
at WARN level and scrolls past unnoticed. This exercise set builds the muscle to reason about
the TF tree topology, understand time interpolation, and write broadcasters and listeners from
scratch.
A1. What is the difference between a StaticTransformBroadcaster and a
TransformBroadcaster? When should you use each?
A2. A lookupTransform call throws tf2_ros.ExtrapolationException. What does this
exception mean physically? Describe two different conditions that trigger it.
A3. Why does time=rclpy.time.Time() (time = zero / “latest available”) work
correctly for static frames but can give wrong results for dynamic frames?
# Use the scan's own timestamp, not Time()
lookupTransform('odom', 'laser_link', scan_msg.header.stamp, timeout=Duration(seconds=0.1))
A4. What causes a ConnectivityException?
ros2 run tf2_tools view_frames # generates frames.pdf showing the tree topology
ros2 topic echo /tf --once # see what transforms are being published right now
A5. How do you check which frames exist in the TF tree from the command line? Give two commands and explain what each shows.
ros2 run tf2_tools view_frames
ros2 topic echo /tf_static --once
ros2 topic echo /tf --once
ros2 run tf2_ros tf2_echo map base_link
The robot below has four nodes publishing into the TF tree:
Static TF broadcaster (URDF): base_link → laser_link
(offset: x=0.3m, y=0, z=0.1m, no rotation)
Odometry node: odom → base_link
(updates at 50Hz as robot moves)
AMCL localization: map → odom
(updates at ~5Hz from laser scan matching)
Answer the four questions below without running any code — reason from the tree topology.
B1. A costmap node needs to insert a laser scan point into the map frame. The point
is at (1.0, 0.0) in laser_link. What is the full chain of transforms applied?
In what order are they composed?
laser_link → base_link → odom → map
P_map = T(map→odom) × T(odom→base_link) × T(base_link→laser_link) × P_laser
B2. AMCL crashes and stops publishing /tf. After 11 seconds, what exceptions will
lookupTransform('map', 'base_link', Time()) throw and why?
B3. You want to know the robot’s laser position relative to the odom frame (not
map). AMCL is not running. Is this lookup possible? What is the risk of using it for
autonomous navigation?
t = tf_buffer.lookup_transform('odom', 'laser_link', Time())
B4. A node requests lookupTransform('odom', 'map', stamp) instead of
lookupTransform('map', 'odom', stamp). What is the difference in the result?
Write a complete Python ROS2 node that broadcasts a static transform:
base_linkcamera_linkimport rclpy
from rclpy.node import Node
# TODO: remaining imports
class StaticCameraPublisher(Node):
def __init__(self):
super().__init__('static_camera_tf')
# TODO: create StaticTransformBroadcaster
# TODO: build TransformStamped with correct values
# TODO: broadcast it
def main(args=None):
rclpy.init(args=args)
node = StaticCameraPublisher()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
import rclpy
from rclpy.node import Node
from tf2_ros import StaticTransformBroadcaster
from geometry_msgs.msg import TransformStamped
import math
class StaticCameraPublisher(Node):
def __init__(self):
super().__init__('static_camera_tf')
self._broadcaster = StaticTransformBroadcaster(self)
t = TransformStamped()
t.header.stamp = self.get_clock().now().to_msg()
t.header.frame_id = 'base_link'
t.child_frame_id = 'camera_link'
# Translation
t.transform.translation.x = 0.1
t.transform.translation.y = 0.0
t.transform.translation.z = 0.5
# Identity rotation (no rotation)
t.transform.rotation.x = 0.0
t.transform.rotation.y = 0.0
t.transform.rotation.z = 0.0
t.transform.rotation.w = 1.0
self._broadcaster.sendTransform(t)
self.get_logger().info('Static transform base_link → camera_link published.')
def main(args=None):
rclpy.init(args=args)
node = StaticCameraPublisher()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
Write a node that simulates a robot driving in a circle. Every 50 ms, compute and broadcast
the odom → base_link transform.
Robot parameters: - Speed: 0.5 m/s along the circumference - Circle radius: 2.0 m - Starting position: (2.0, 0.0) — on the positive X axis relative to the circle centre - Heading: initially pointing in the +Y direction (tangent to the circle)
The angular velocity is ω = v / r. Update θ each tick by ω × dt.
import rclpy
from rclpy.node import Node
import math
# TODO: remaining imports
class CircleBroadcaster(Node):
def __init__(self):
super().__init__('circle_broadcaster')
self._angle = 0.0 # current angle around the circle (radians)
self._radius = 2.0
self._speed = 0.5 # m/s along circumference
self._dt = 0.05 # 50ms
# TODO: create TransformBroadcaster
# TODO: create 20Hz timer (dt=0.05s)
def timer_cb(self):
# TODO: advance self._angle by omega * dt
# TODO: compute x = radius * cos(angle), y = radius * sin(angle)
# TODO: robot heading = angle + pi/2 (tangent to circle)
# TODO: build TransformStamped, fill translation and rotation (yaw only)
# TODO: broadcast
pass
def main(args=None):
rclpy.init(args=args)
node = CircleBroadcaster()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
import rclpy
from rclpy.node import Node
from tf2_ros import TransformBroadcaster
from geometry_msgs.msg import TransformStamped
import math
class CircleBroadcaster(Node):
def __init__(self):
super().__init__('circle_broadcaster')
self._angle = 0.0
self._radius = 2.0
self._speed = 0.5 # m/s
self._dt = 0.05 # seconds
self._broadcaster = TransformBroadcaster(self)
self._timer = self.create_timer(self._dt, self.timer_cb)
def timer_cb(self):
omega = self._speed / self._radius # rad/s
self._angle += omega * self._dt
x = self._radius * math.cos(self._angle)
y = self._radius * math.sin(self._angle)
yaw = self._angle + math.pi / 2 # tangent heading
t = TransformStamped()
t.header.stamp = self.get_clock().now().to_msg()
t.header.frame_id = 'odom'
t.child_frame_id = 'base_link'
t.transform.translation.x = x
t.transform.translation.y = y
t.transform.translation.z = 0.0
# Convert yaw to quaternion (rotation around Z only)
t.transform.rotation.x = 0.0
t.transform.rotation.y = 0.0
t.transform.rotation.z = math.sin(yaw / 2.0)
t.transform.rotation.w = math.cos(yaw / 2.0)
self._broadcaster.sendTransform(t)
def main(args=None):
rclpy.init(args=args)
node = CircleBroadcaster()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
Write a node that every second looks up the transform from map to base_link and prints
the robot’s (x, y, yaw_degrees) to the console. Handle all three TF2 exception types with
informative messages.
import rclpy
from rclpy.node import Node
import math
# TODO: remaining imports — Buffer, TransformListener, and all three exception types
class PoseReporter(Node):
def __init__(self):
super().__init__('pose_reporter')
# TODO: create tf2_ros.Buffer and tf2_ros.TransformListener
# TODO: create 1Hz timer
def timer_cb(self):
try:
# TODO: lookupTransform('map', 'base_link', rclpy.time.Time())
# TODO: extract x, y, yaw from the result
# TODO: log the pose
pass
except Exception as e:
# TODO: catch LookupException, ConnectivityException, ExtrapolationException
# separately with informative messages
pass
def main(args=None):
rclpy.init(args=args)
node = PoseReporter()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
import rclpy
from rclpy.node import Node
from rclpy.duration import Duration
import tf2_ros
import math
class PoseReporter(Node):
def __init__(self):
super().__init__('pose_reporter')
self._tf_buffer = tf2_ros.Buffer()
self._tf_listener = tf2_ros.TransformListener(self._tf_buffer, self)
self._timer = self.create_timer(1.0, self.timer_cb)
def timer_cb(self):
try:
t = self._tf_buffer.lookup_transform(
'map',
'base_link',
rclpy.time.Time(), # latest available
)
x = t.transform.translation.x
y = t.transform.translation.y
qz = t.transform.rotation.z
qw = t.transform.rotation.w
yaw = math.degrees(2.0 * math.atan2(qz, qw))
self.get_logger().info(
f'Robot pose: x={x:.3f}m y={y:.3f}m yaw={yaw:.1f}°'
)
except tf2_ros.LookupException as e:
self.get_logger().warn(
f'LookupException: frame "map" or "base_link" has never been published. '
f'Details: {e}'
)
except tf2_ros.ConnectivityException as e:
self.get_logger().warn(
f'ConnectivityException: no connected path from "base_link" to "map" '
f'in the TF tree. Is localization running? Details: {e}'
)
except tf2_ros.ExtrapolationException as e:
self.get_logger().warn(
f'ExtrapolationException: requested time is outside the TF buffer window. '
f'Localization may have stalled. Details: {e}'
)
def main(args=None):
rclpy.init(args=args)
node = PoseReporter()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()