ros / geometry2

A set of ROS packages for keeping track of coordinate transforms.
191 stars 279 forks source link

TransformListener: ability to subscribe to arbitrary TF topic #69

Closed ZdenekM closed 10 years ago

ZdenekM commented 10 years ago

I found out that for some multirobot experiments it would be nice to have ability to construct TransformListener which will listen to arbitrary TF topic (let's say /robot1/tf instead of /tf). This change should be very simple - I would add another constructor with parameters for tf and tf_static and use provided topics in TransformListener::init(). If no one has objection, I can prepare pull request. Or is this completely silly idea? :) Originally, I wanted to derive custom class from TransformListener but the problem is that message_subscriber_tf_ and message_subscriber_tf_static_ are private so init method can't be overridden.

tfoote commented 10 years ago

Most use cases simply use the remapping arguments. Is that not adequate for your use case?

ZdenekM commented 10 years ago

I'm working on kind of multirobot monitoring tool but I want to subscribe only to one robot's TF at the time to save bandwidth. While it would be possible to prepare some node in the middle which may handle "online remapping" (subscribing to /robotX/tf and republishing as /tf) I guess this will lead to strange effects after switch (moreover, there will be some additional - unnecessary processing/delay because of republishing). So I guess that most correct approach will be always recreate TransformListener listening to appropriate topics (or fixed topics but in specified namespace, e.g. /robotX).

tfoote commented 10 years ago

I think you can actually do this already by passing in a custom node_handle with the appropriate remappings applied to it but not to the general use one.

ZdenekM commented 10 years ago

Thanks Tully, I completely missed this possibility. I will give it a try.

miguelriemoliveira commented 1 year ago

Hello,

I wanted to have a node which has a tf listener object that listens to topics /tf and /tf_static, and, in the same node, have a second listener that listens to tranformations on different topics, e.g. /ground_truth/tf and /ground_truth/tf_static.

I read you suggestion above but don't know how to create a node handle with remapped arguments.

Do you have any suggestions how I could do this?

Thanks in advance, Miguel

miguelriemoliveira commented 1 year ago

Got it. I will write it down here. It may hep others.

First, I created a class called ConfigurableTransformListener which inherits from standard TransformListener. Then, the ConfigurableTransformListener overwrites the constructor, defining which tf and tf_static topics to use.

Seems to be working. Here's the code.

import rospy
from time import sleep
import threading
from tf2_msgs.msg import TFMessage
import tf2_ros

class ConfigurableTransformListener(tf2_ros.TransformListener):

    def __init__(self, buffer, queue_size=None, buff_size=65536, tcp_nodelay=False, tf_topic='tf', tf_static_topic='tf_static'):

        # Copy past the code from the tf2_ros.TransformListener constructor method, changing the subscribed topics.
        self.buffer = buffer
        self.last_update = rospy.Time.now()
        self.last_update_lock = threading.Lock()
        self.tf_sub = rospy.Subscriber(tf_topic, TFMessage, self.callback,
                                       queue_size=queue_size, buff_size=buff_size, tcp_nodelay=tcp_nodelay)
        self.tf_static_sub = rospy.Subscriber(tf_static_topic, TFMessage, self.static_callback,
                                              queue_size=queue_size, buff_size=buff_size, tcp_nodelay=tcp_nodelay)

def main():

    rospy.init_node('dual_tf_listener', anonymous=False)

    tfBuffer = tf2_ros.Buffer()
    # listener = tf2_ros.TransformListener(tfBuffer) # this is the conventional way.
    listener = ConfigurableTransformListener(tfBuffer, tf_topic='tf_ground_truth',
                                             tf_static_topic='tf_static_ground_truth')

    rate = rospy.Rate(3.0)
    while not rospy.is_shutdown():
        try:
            trans = tfBuffer.lookup_transform('world', 'shoulder_link', rospy.Time())
            print(trans)
        except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException):
            print('Could not get transform')
            continue

        print('sleeping')
        sleep(1)

if __name__ == '__main__':
    main()
nishantm-jlg commented 8 months ago

One can do it by running your code as ros2 run <package_name> <node_name>.py --ros-args --remap tf:=<new tf topic name>. It can also be done from a launch file.