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

lookup_transform: TypeError: __init__() takes 1 positional argument but 2 were given

asked 2021-08-30 00:47:29 -0500

dasishere gravatar image

updated 2021-08-30 23:40:45 -0500

Hi all, I am using ROS2 Foxy in Ubuntu 20.04 LTS. I am trying to fetch the robot's pose with respect to the odom frame. Here is my code.

import rclpy
from rclpy.time import Time
from rclpy.node import Node
from rclpy.duration import Duration
from geometry_msgs.msg import Pose
from geometry_msgs.msg import TransformStamped
from tf2_ros.transform_listener import TransformListener
from tf2_ros.buffer import Buffer
from rclpy.duration import Duration

class Trial(Node):
    def __init__(self):
        super().__init__('trial_node')
        self.pose = TransformStamped()
        self._tf_buffer = Buffer()
        self.listener = TransformListener(self._tf_buffer, self)

    def get_global_pos(self):
        now = Time()
        try:
            self.get_logger().info("Fetching transform of 'base_link' with reference to 'odom' frame.")
            trans = self._tf_buffer.lookup_transform('odom', 'base_link', time=Duration(0))
            print(trans)
        except LookupError:
            self.get_logger().info('Transform between odom and base_link not ready...')

    return

def main():
    rclpy.init()
    node = Trial()
    while not rclpy.shutdown():
        try:
            node.get_global_pos()
            rclpy.spin_once(node)
        except KeyboardInterrupt:
            rclpy.shutdown()  
   return

if __name__=='__main__':
    main()

I get the following error:

ros2 run trial trial 
[INFO] [1630305124.566534260] [trial_node]: Fetching transform of 'base_link' with reference to 'odom' frame.
Traceback (most recent call last):
  File "/home/adas/Documents/Ayush/dev/intman-proj/dev_ros/nokia_im_ws/install/trial/lib/trial/trial", line 11, in <module>
    load_entry_point('trial==0.0.0', 'console_scripts', 'trial')()
  File "/home/adas/Documents/Ayush/dev/intman-proj/dev_ros/nokia_im_ws/install/trial/lib/python3.8/site-packages/trial/trial.py", line 49, in main
    pose = get_global_pose(tf_buffer, node)
  File "/home/adas/Documents/Ayush/dev/intman-proj/dev_ros/nokia_im_ws/install/trial/lib/python3.8/site-packages/trial/trial.py", line 33, in get_global_pose
    trans = _tf_buffer.lookup_transform('odom', 'base_link', Duration(0))
TypeError: __init__() takes 1 positional argument but 2 were given

The line seems to cause this error.

trans = self._tf_buffer.lookup_transform('odom', 'base_link', time=Duration(0))

I believe the error is thrown by the buffer.py file, but I am not too sure about it.

class Buffer(tf2.BufferCore, tf2_ros.BufferInterface):
    """
    Standard implementation of the :class:`tf2_ros.BufferInterface` abstract data type.

    Inherits from :class:`tf2_ros.buffer_interface.BufferInterface` and :class:`tf2.BufferCore`.

    Stores known frames and offers a ROS service, "tf_frames", which responds to client requests
    with a response containing a :class:`tf2_msgs.FrameGraph` representing the relationship of
    known frames. 
    """

    def __init__(self, cache_time = None, node = None):
        """
        Constructor.

        :param cache_time: (Optional) How long to retain past information in BufferCore.
        :param node: (Optional) If node create a tf2_frames service, It responses all frames as a yaml
        """
        if cache_time is not None:
            tf2.BufferCore.__init__(self, cache_time)
        else:
            tf2.BufferCore.__init__(self)
        tf2_ros.BufferInterface.__init__(self)

        self._new_data_callbacks = []
        self._callbacks_to_remove = []
        self._callbacks_lock = threading.RLock()

        if node is not None:
            self.srv = node.create_service(FrameGraph, 'tf2_frames', self.__get_frames)


    def lookup_transform(self, target_frame, source_frame, time, timeout=Duration()):
        """
        Get the transform from the source frame to the target frame.

        :param target_frame: Name of the frame to transform into.
        :param source_frame: Name of the input frame.
        :param time: The time at which to get the transform. (0 will get the latest) 
        :param timeout: (Optional) Time to wait for the ...
(more)
edit retag flag offensive close merge delete

Comments

I get the following error:

TypeError: __init__() takes 1 positional argument but 2 were given

please do not paraphrase or edit error messages.

Especially in Python, tracebacks contains all sorts of important information. By only showing the message, you make it harder for others to help you, as they now have to guess where that exception is thrown (and/or trust you got it right).

Just copy-paste the complete traceback into your question.

gvdhoorn gravatar image gvdhoorn  ( 2021-08-30 03:30:48 -0500 )edit

Hey gvdhoorn, apologies for the lack of clarity. I have edited the error as per your suggestion. Hope this gives more clarity.

dasishere gravatar image dasishere  ( 2021-08-30 23:32:51 -0500 )edit

1 Answer

Sort by » oldest newest most voted
0

answered 2021-08-31 03:47:19 -0500

kurshakuz gravatar image

updated 2021-09-01 02:11:38 -0500

The problem is that your are not passing parameters correctly here. As you have added in your question, lookup_transform() takes following pararmeters:

    :param target_frame: Name of the frame to transform into.
    :param source_frame: Name of the input frame.
    :param time: The time at which to get the transform. (0 will get the latest) 
    :param timeout: (Optional) Time to wait for the ...

Here the first three (target frame, source frame, time at which to get the transform) are required and the last one is optional (timeout). In your code, you probably confused a timeout and time parameters. You have to pass a Time() to the time parameter and Duration() to the timeout parameter. Therefore, your lookup_transform() call should actually look like:

 timeToLookUp = rclpy.time.Time() # to acquire the last transform
 trans = self._tf_buffer.lookup_transform('odom', 'base_link', timeToLookUp, timeout=Duration(seconds=0.0))

btw, if you are interested in some code examples or advanced concept on tf2, you can look here https://docs.ros.org/en/rolling/Tutor... ;)

edit flag offensive delete link more

Comments

Hi kurshakuz, thank you for your answer. I have tried what you have suggested but unfortunately I am still facing the same error message.

dasishere gravatar image dasishere  ( 2021-08-31 05:15:34 -0500 )edit

did you rebuild your package? This error must have disappeared. Can you show your full error output?

kurshakuz gravatar image kurshakuz  ( 2021-08-31 05:30:47 -0500 )edit

Yes, I have re-built the workspace. Below is the error message for your reference.

Traceback (most recent call last):
  File "/home/adas/Documents/Ayush/dev/intman-proj/dev_ros/nokia_im_ws/install/trial/lib/trial/trial", line 11, in <module>
    load_entry_point('trial==0.0.0', 'console_scripts', 'trial')()
  File "/home/adas/Documents/Ayush/dev/intman-proj/dev_ros/nokia_im_ws/install/trial/lib/python3.8/site-packages/trial/trial.py", line 33, in main
    node.get_global_pos()
  File "/home/adas/Documents/Ayush/dev/intman-proj/dev_ros/nokia_im_ws/install/trial/lib/python3.8/site-packages/trial/trial.py", line 22, in get_global_pos
    trans = self._tf_buffer.lookup_transform('odom', 'base_link', time=Time(), timeout=Duration(0))
TypeError: __init__() takes 1 positional argument but 2 were given
dasishere gravatar image dasishere  ( 2021-08-31 05:42:03 -0500 )edit

I see the problem with that. You don't need to specify names of required parameters in Python (in this case time). Just use trans = self._tf_buffer.lookup_transform('odom', 'base_link', rclpy.time.Time(), timeout=Duration(0))

kurshakuz gravatar image kurshakuz  ( 2021-08-31 05:49:07 -0500 )edit

Unfortunately, the same error again.

Traceback (most recent call last):
  File "/home/adas/Documents/Ayush/dev/intman-proj/install/trial/lib/trial/trial", line 11, in <module>
    load_entry_point('trial==0.0.0', 'console_scripts', 'trial')()
  File "/home/adas/Documents/Ayush/dev/intman-proj/install/trial/lib/python3.8/site-packages/trial/trial.py", line 33, in main
    node.get_global_pos()
  File "/home/adas/Documents/Ayush/dev/intman-proj/install/trial/lib/python3.8/site-packages/trial/trial.py", line 22, in get_global_pos
    trans = self._tf_buffer.lookup_transform('odom', 'base_link', Time(), timeout=Duration(0))
TypeError: __init__() takes 1 positional argument but 2 were given
dasishere gravatar image dasishere  ( 2021-08-31 05:56:39 -0500 )edit

Apparently the issue is with the way Duration() is called. You have to specify seconds or nanoseconds as timeout=Duration(seconds=0.0)

kurshakuz gravatar image kurshakuz  ( 2021-08-31 07:53:21 -0500 )edit

I tried that, I am getting a different error right now.

Traceback (most recent call last):

File "/home/adas/Documents/Ayush/dev/intman-proj/install/trial/lib/trial/trial", line 11, in <module>
    load_entry_point('trial==0.0.0', 'console_scripts', 'trial')()
  File "/home/adas/Documents/Ayush/dev/intman-proj/install/trial/lib/python3.8/site-packages/trial/trial.py", line 37, in main
    node.get_global_pos()
  File "/home/adas/Documents/Ayush/dev/intman-proj/install/trial/lib/python3.8/site-packages/trial/trial.py", line 26, in get_global_pos
    trans = self._tf_buffer.lookup_transform(self.target_frame, self.initial_frame, Time(), timeout=Duration(nanoseconds=0.0))
  File "/opt/ros/foxy/lib/python3.8/site-packages/tf2_ros/buffer.py", line 112, in lookup_transform
    return self.lookup_transform_core(target_frame, source_frame, time)
tf2.LookupException: "odom" passed to lookupTransform argument target_frame does not exist.
dasishere gravatar image dasishere  ( 2021-08-31 23:30:46 -0500 )edit

This is how my tf tree looks like. base_footprint broadcasts to base_link only at 0.0 seconds as you see in the image and is done only once. I tried doing Time(0) to get the latest transform but it throws an error saying the same as the error message that I comment just before this.

dasishere gravatar image dasishere  ( 2021-08-31 23:33:09 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-08-30 00:47:29 -0500

Seen: 2,386 times

Last updated: Sep 01 '21