tf2_ros.transform_listener module

class tf2_ros.transform_listener.TransformListener[source]

Bases: object

TransformListener receives transforms.

It is a convenient way to listen for coordinate frame transformation info. This class takes an object that instantiates the BufferInterface interface, to which it propagates changes to the tf frame graph. It listens to both static and dynamic transforms.

__init__(buffer: Buffer, node: rclpy.node.Node, *, spin_thread: bool = False, qos: rclpy.qos.QoSProfile | int | None = None, static_qos: rclpy.qos.QoSProfile | int | None = None, tf_topic: str = '/tf', tf_static_topic: str = '/tf_static', static_only: bool = False) None[source]

Construct the TransformListener.

Parameters:
  • buffer – The buffer to propagate changes to when tf info updates.

  • node – The ROS2 node.

  • spin_thread – Whether to create a dedidcated thread to spin this node.

  • qos – A QoSProfile or a history depth to apply to subscribers.

  • static_qos – A QoSProfile or a history depth to apply to tf_static subscribers.

  • tf_topic – Which topic to listen to for dynamic transforms.

  • tf_static_topic – Which topic to listen to for static transforms.

  • static_only – A bool which allows the listener to be strictly static.

callback(data: tf2_msgs.msg.TFMessage) None[source]
static_callback(data: tf2_msgs.msg.TFMessage) None[source]
unregister() None[source]

Unregisters all tf subscribers.