Skip to content

Commit

Permalink
Add configurable TF topics (#709)
Browse files Browse the repository at this point in the history
* Set defaults in transform lister and expose them as args to the
  TransformLister
* Add CLI args in view_frames to change /tf and /tf_static topics

Signed-off-by: Ryan Friedman <25047695+Ryanf55@users.noreply.github.com>
  • Loading branch information
Ryanf55 authored Oct 15, 2024
1 parent b4d8dfb commit 5911417
Show file tree
Hide file tree
Showing 3 changed files with 27 additions and 5 deletions.
7 changes: 7 additions & 0 deletions tf2_ros/doc/cli_tools.rst
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,13 @@ In the current working folder, you should now have a file called "frames_$(data)

.. image:: images/view_frames.png


If you need to view the frames from non-standard topics, you can override them like so:

.. code-block:: bash
ros2 run tf2_tools view_frames --tf_topic=/foo --tf_static_topic=bar
Fields
~~~~~~
* Recorded at time: shows the absolute timestamp when this graph was generated.
Expand Down
15 changes: 11 additions & 4 deletions tf2_ros_py/tf2_ros/transform_listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,12 +40,15 @@
from tf2_msgs.msg import TFMessage
from threading import Thread

DEFAULT_TF_TOPIC = '/tf'
DEFAULT_STATIC_TF_TOPIC = '/tf_static'

class TransformListener:
"""
:class:`TransformListener` is a convenient way to listen for coordinate frame transformation info.
This class takes an object that instantiates the :class:`BufferInterface` interface, to which
it propagates changes to the tf frame graph.
it propagates changes to the tf frame graph. It listens to both static and dynamic
transforms.
"""
def __init__(
self,
Expand All @@ -54,7 +57,9 @@ def __init__(
*,
spin_thread: bool = False,
qos: Optional[Union[QoSProfile, int]] = None,
static_qos: Optional[Union[QoSProfile, int]] = None
static_qos: Optional[Union[QoSProfile, int]] = None,
tf_topic: str = DEFAULT_TF_TOPIC,
tf_static_topic: str = DEFAULT_STATIC_TF_TOPIC
) -> None:
"""
Constructor.
Expand All @@ -64,6 +69,8 @@ def __init__(
:param spin_thread: Whether to create a dedidcated thread to spin this node.
:param qos: A QoSProfile or a history depth to apply to subscribers.
:param static_qos: A QoSProfile or a history depth to apply to tf_static subscribers.
:param tf_topic: Which topic to listen to for dynamic transforms.
:param tf_static_topic: Which topic to listen to for static transforms.
"""
if qos is None:
qos = QoSProfile(
Expand All @@ -83,9 +90,9 @@ def __init__(
# from another callback in the same group.
self.group = ReentrantCallbackGroup()
self.tf_sub = node.create_subscription(
TFMessage, '/tf', self.callback, qos, callback_group=self.group)
TFMessage, tf_topic, self.callback, qos, callback_group=self.group)
self.tf_static_sub = node.create_subscription(
TFMessage, '/tf_static', self.static_callback, static_qos, callback_group=self.group)
TFMessage, tf_static_topic, self.static_callback, static_qos, callback_group=self.group)

if spin_thread:
self.executor = SingleThreadedExecutor()
Expand Down
10 changes: 9 additions & 1 deletion tf2_tools/tf2_tools/view_frames.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
import rclpy
from tf2_msgs.srv import FrameGraph
import tf2_ros
from tf2_ros.transform_listener import DEFAULT_STATIC_TF_TOPIC, DEFAULT_TF_TOPIC

import yaml

Expand All @@ -50,12 +51,19 @@ def main():
'--wait-time', '-t', type=float, default=5.0,
help='Listen to the /tf topic for this many seconds before rendering the frame tree')
parser.add_argument('-o', '--output', help='Output filename')
parser.add_argument('--tf_topic', help='Topic for dynamic transforms',
default=DEFAULT_TF_TOPIC)
parser.add_argument('--tf_static_topic', help='Topic for static transforms',
default=DEFAULT_STATIC_TF_TOPIC)

parsed_args = parser.parse_args(args=args_without_ros[1:])

node = rclpy.create_node('view_frames')

buf = tf2_ros.Buffer(node=node)
listener = tf2_ros.TransformListener(buf, node, spin_thread=False)
listener = tf2_ros.TransformListener(buf, node, spin_thread=False,
tf_topic=parsed_args.tf_topic,
tf_static_topic=parsed_args.tf_static_topic)
listener # To quiet a flake8 warning

executor = rclpy.executors.SingleThreadedExecutor()
Expand Down

0 comments on commit 5911417

Please sign in to comment.