Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adding StaticTransformListener in Python #719

Merged
merged 4 commits into from
Nov 7, 2024
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions tf2_ros_py/test/test_listener_and_broadcaster.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
from tf2_ros.transform_broadcaster import TransformBroadcaster
from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster
from tf2_ros.transform_listener import TransformListener
from tf2_ros.static_transform_listener import StaticTransformListener
from tf2_ros import ExtrapolationException


Expand Down Expand Up @@ -67,6 +68,8 @@ def setup_class(cls):
cls.static_broadcaster = StaticTransformBroadcaster(cls.node)
cls.listener = TransformListener(
buffer=cls.buffer, node=cls.node, spin_thread=False)
cls.static_listener = StaticTransformListener(
buffer=cls.buffer, node=cls.node, spin_thread=False)

cls.executor = rclpy.executors.SingleThreadedExecutor()
cls.executor.add_node(cls.node)
Expand Down
111 changes: 111 additions & 0 deletions tf2_ros_py/tf2_ros/static_transform_listener.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,111 @@
# Copyright (c) 2008, Willow Garage, Inc.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
# Copyright (c) 2008, Willow Garage, Inc.
# Copyright (c) 2024, Open Source Robotics Foundation, Inc.

# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in the
# documentation and/or other materials provided with the distribution.
# * Neither the name of the Willow Garage, Inc. nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

# author: Wim Meeussen
CursedRock17 marked this conversation as resolved.
Show resolved Hide resolved
from typing import Optional
from typing import Union

from rclpy.node import Node
from rclpy.callback_groups import ReentrantCallbackGroup
from rclpy.executors import SingleThreadedExecutor
from rclpy.qos import DurabilityPolicy
from rclpy.qos import HistoryPolicy
from rclpy.qos import QoSProfile
from tf2_ros.buffer import Buffer
from tf2_msgs.msg import TFMessage
from threading import Thread

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


class StaticTransformListener:
"""
:class:`StaticTransformListener` is a convenient way to establish a TransformListener on only static topics.
"""

def __init__(
self,
buffer: Buffer,
node: Node,
*,
spin_thread: bool = False,
static_qos: Optional[Union[QoSProfile, int]] = None,
tf_static_topic: str = DEFAULT_STATIC_TF_TOPIC
) -> None:
"""
Constructor.
:param buffer: The buffer to propagate changes to when tf info updates.
:param node: The ROS2 node.
CursedRock17 marked this conversation as resolved.
Show resolved Hide resolved
:param spin_thread: Whether to create a dedidcated thread to spin this node.
:param static_qos: A QoSProfile or a history depth to apply to tf_static subscribers.
:param tf_static_topic: Which topic to listen to for static transforms.
"""
if static_qos is None:
static_qos = QoSProfile(
depth=100,
durability=DurabilityPolicy.TRANSIENT_LOCAL,
history=HistoryPolicy.KEEP_LAST,
)
self.buffer = buffer
self.node = node
# Default callback group is mutually exclusive, which would prevent waiting for transforms
# from another callback in the same group.
self.group = ReentrantCallbackGroup()

self.tf_static_sub = node.create_subscription(
TFMessage, tf_static_topic, self.static_callback, static_qos, callback_group=self.group)

if spin_thread:
self.executor = SingleThreadedExecutor()

def run_func():
self.executor.add_node(self.node)
self.executor.spin()
self.executor.remove_node(self.node)

self.dedicated_listener_thread = Thread(target=run_func)
self.dedicated_listener_thread.start()

def __del__(self) -> None:
if hasattr(self, 'dedicated_listener_thread') and hasattr(self, 'executor'):
self.executor.shutdown()
self.dedicated_listener_thread.join()

self.unregister()

def unregister(self) -> None:
"""
Unregisters all tf_static subscribers.
"""
self.node.destroy_subscription(self.tf_static_sub)

def static_callback(self, data: TFMessage) -> None:
who = 'default_authority'
for transform in data.transforms:
self.buffer.set_transform_static(transform, who)
25 changes: 16 additions & 9 deletions tf2_ros_py/tf2_ros/transform_listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ class TransformListener:
it propagates changes to the tf frame graph. It listens to both static and dynamic
transforms.
"""

def __init__(
self,
buffer: Buffer,
Expand All @@ -59,7 +60,8 @@ def __init__(
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
tf_static_topic: str = DEFAULT_STATIC_TF_TOPIC,
static_only: bool = False
) -> None:
"""
Constructor.
Expand All @@ -71,13 +73,8 @@ def __init__(
: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.
:param static_only: A bool which allows the listener to be strictly static.
"""
if qos is None:
qos = QoSProfile(
depth=100,
durability=DurabilityPolicy.VOLATILE,
history=HistoryPolicy.KEEP_LAST,
)
if static_qos is None:
static_qos = QoSProfile(
depth=100,
Expand All @@ -89,8 +86,18 @@ def __init__(
# Default callback group is mutually exclusive, which would prevent waiting for transforms
# from another callback in the same group.
self.group = ReentrantCallbackGroup()
self.tf_sub = node.create_subscription(
TFMessage, tf_topic, self.callback, qos, callback_group=self.group)

# Turn the class into a StaticTransformListener by enabling static_only.
if static_only is False:
if qos is None:
qos = QoSProfile(
depth=100,
durability=DurabilityPolicy.VOLATILE,
history=HistoryPolicy.KEEP_LAST,
)
self.tf_sub = node.create_subscription(
TFMessage, tf_topic, self.callback, qos, callback_group=self.group)

self.tf_static_sub = node.create_subscription(
TFMessage, tf_static_topic, self.static_callback, static_qos, callback_group=self.group)

Expand Down