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

tf2: I can broadcast transfroms but I cannot listen to them. I keep getting [ERROR] : Lookup would require extrapolation

asked 2020-12-08 15:08:28 -0500

Forenkazan gravatar image

Hello

I am trying to do a simple broadcast/listen of tf2 where I broadcast a frame and then listen to it and transform a point in that frame. However, the broadcasting script is working as intended but I cannot listen to it and I keep getting:

[ERROR] [1607460129.073986]: Lookup would require extrapolation 0.009213686s into the past.  Requested time 1607460126.067262173 but the earliest data is at time 1607460126.076475859, when looking up transform from frame [base_laser] to frame [base_link]

Here are the two scripts:

Broadcaster:

import rospy
import tf2_ros
import geometry_msgs.msg
from tf.transformations import *
import tf_conversions


if __name__ == "__main__":
    rospy.init_node('tf2_turtle_broadcaster')
    rate = rospy.Rate(100)

    while not rospy.is_shutdown():

        broadcaster = tf2_ros.TransformBroadcaster()

        t = geometry_msgs.msg.TransformStamped()
        t.header.stamp = rospy.Time.now()
        t.header.frame_id = "base_link"
        t.child_frame_id = "base_laser"
        t.transform.rotation = geometry_msgs.msg.Quaternion(0, 0, 0, 1)
        t.transform.translation = geometry_msgs.msg.Vector3(0.1, 0, 0.2)

        broadcaster.sendTransform(t)
        rate.sleep()

Listener:

import rospy

import tf2_ros
import geometry_msgs.msg
from tf2_geometry_msgs import PointStamped

from tf.transformations import *

if __name__ == "__main__":

    rospy.init_node('robot_tf_listener')

    laser_point = PointStamped()
    laser_point.header.stamp = rospy.Time.now()
    laser_point.header.frame_id = "base_laser"
    laser_point.point.x = 1
    laser_point.point.y = 0.2
    laser_point.point.z = 0

    tfBuffer = tf2_ros.Buffer()
    listener = tf2_ros.TransformListener(tfBuffer)

    rate = rospy.Rate(10)
    while not rospy.is_shutdown():
        try:
            rospy.loginfo('1')
            tran = tfBuffer.transform(laser_point, "base_link", timeout=rospy.Duration(3))
            rospy.loginfo('2')

        except Exception as e:
            rospy.logerr(e)

        rate.sleep()
edit retag flag offensive close merge delete

Comments

Are you using two different machines? If so, this may have to do with the machines not having their clocks synced. See the network setup on the wiki.

jayess gravatar image jayess  ( 2020-12-08 17:44:49 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-12-08 16:44:01 -0500

apawlica gravatar image

Use Time(0) instead of Time.now(). For more detail, check out the following: http://wiki.ros.org/tf/Tutorials/tf%2...

edit flag offensive delete link more

Comments

The op is using tf2 and the tutorial that you're linking to is the deprecated tf package.

jayess gravatar image jayess  ( 2020-12-08 17:42:52 -0500 )edit

Wouldn't the relevant bit (using Time(0) instead of Time.now()) still be applicable, as it's a timing issue and not unique to tf2?

apawlica gravatar image apawlica  ( 2020-12-08 18:04:08 -0500 )edit
jayess gravatar image jayess  ( 2020-12-08 18:24:50 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-12-08 15:08:28 -0500

Seen: 909 times

Last updated: Dec 08 '20