ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

tf2_ros: AttributeError: 'Buffer' object has no attribute 'destroy_subscription'

asked 2020-12-14 17:58:53 -0500

FKNoble gravatar image

Hi there,

I'm new to ROS and am working through all the tutorials. Right now, I'm working on the tf2 package's tutorials; however, I'm getting stuck on writing a tf2 listener (see: http://wiki.ros.org/tf2/Tutorials/Wri...).

I've written the following code to create a listener:

import rclpy
import tf2_ros

from rclpy.node import Node
from rclpy.qos import QoSProfile

class Subscriber(Node):

    def __init__(self):
        super().__init__('subscriber')
        qos_profile = QoSProfile(depth=10)

        self.buffer = tf2_ros.Buffer()
        self.listener = tf2_ros.TransformListener(self, self.buffer)

        self.timer = self.create_timer(0.5, self.timer_callback)
        self.get_logger().info('Starting {}'.format(self.get_name()))
        self.i = 0

        return

    def timer_callback(self):

        try:
            trans = self.buffer.lookup_transform('frame_1', 'frame_2', 0)
        except Exception as e:
            self.get_logger('Error')

        self.get_logger().info('{}: Transform: {}'.format(self.i, trans))
        self.i += 1

        return


def main(args=None):

    rclpy.init(args=args)

    subscriber = Subscriber()

    rclpy.spin(subscriber)

    subscriber.destroy_node()
    rclpy.shutdown()

    return


if __name__ == "__main__":
    main()

This is creating the following error:

Traceback (most recent call last):
  File "/home/fknoble/dev_ws/install/learning_tf2/lib/learning_tf2/sub", line 11, in <module>
    load_entry_point('learning-tf2==0.0.0', 'console_scripts', 'sub')()
  File "/home/fknoble/dev_ws/install/learning_tf2/lib/python3.8/site-packages/learning_tf2/sub.py", line 39, in main
    subscriber = Subscriber()
  File "/home/fknoble/dev_ws/install/learning_tf2/lib/python3.8/site-packages/learning_tf2/sub.py", line 14, in __init__
    self.listener = tf2_ros.TransformListener(self, self.buffer)
  File "/opt/ros/foxy/lib/python3.8/site-packages/tf2_ros/transform_listener.py", line 72, in __init__
    self.tf_sub = node.create_subscription(
AttributeError: 'Buffer' object has no attribute 'create_subscription'
Exception ignored in: <function TransformListener.__del__ at 0x7fc54bbe3160>
Traceback (most recent call last):
  File "/opt/ros/foxy/lib/python3.8/site-packages/tf2_ros/transform_listener.py", line 93, in __del__
    self.unregister()
  File "/opt/ros/foxy/lib/python3.8/site-packages/tf2_ros/transform_listener.py", line 99, in unregister
    self.node.destroy_subscription(self.tf_sub)
AttributeError: 'Buffer' object has no attribute 'destroy_subscription'

Because I'm new to this, I'm not sure if the issue is with my code or with the tf2_ros package. I should mention that the frames 'frame_1' and 'frame_2' are being broadcasted successfully (I can view them in RVIZ). Also, my ROS distro' is Foxy, I've installed it in Ubuntu 20.04, and I'm programming with Python 3.8.5.

Any advice would be greatly appreciated,

Frazer

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-12-15 11:39:29 -0500

jacobperron gravatar image

updated 2020-12-15 11:40:24 -0500

You've mixed up the parameters to tf2_ros.TransformListener. The first parameter should should be the buffer and the second parameter should be the node (reference). Try changing your code to:

    self.listener = tf2_ros.TransformListener(self.buffer, self)
edit flag offensive delete link more

Comments

Thank you for your answer, it solved my problem. Also, thanks for the reference/link, it was very helpful.

In addition, once I had changed this line of code, I had to make one more edit to get everything to work. I had to change:

trans = self.buffer.lookup_transform('frame_1', 'frame_2', 0)

to:

trans = self.buffer.lookup_transform('frame_2', 'frame_1', rclpy.time.Time(seconds=0))

Otherwise, I kept getting errors about the transform being in the future.

FKNoble gravatar image FKNoble  ( 2020-12-15 13:57:30 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-12-14 17:58:53 -0500

Seen: 1,338 times

Last updated: Dec 15 '20