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

Extrapolation exception error (tiny time difference)

asked 2021-05-21 06:15:16 -0500

gnomezone gravatar image

Hi, I'm attempting to help some colleagues extract data from a rosbag. I'm running Ubuntu 18.04.5 LTS. A Hokuyo UTM30LX lidar was used to gather a pointcloud, published on the topic /slam_cloud with the message type sensor_msgs/Pointcloud. They would now like to extract the pointcloud data in xyz format or similar format. As the message type is Pointcloud and not Pointcloud2, I cannot use the pcl_ros bag_to_pcd node as I had hoped to.

Instead, I wrote a short script to subscribe to the pointcloud topic, and write each point to an xyz file. The pointcloud topic is published in the /laser_frame, so I would like to transform the data to the /map frame instead. However, when I attempt to use the tf.TransformListener.transformPointCloud() function, I get the following message:

ExtrapolationException: Lookup would require extrapolation into the future.  Requested time 1617028327.692719936 but the latest data is at time 1617028327.642892361, when looking up transform from frame [laser_frame] to frame [map]

The difference between the two times is very small, approximately 0.025 seconds. The topic is published at a rate of 40Hz (every 0.025 seconds) , so to me this seems that somehow the frames are 1 cycle out of sync. Strangely, if I run tf.TransformListener.lookupTransform('/map', '/laser_frame', rospy.Time(0)), then do not get an error message. I'm not quite sure where to proceed from here: as I can get the transform from lookupTransform I could transform between the two that way but I don't if there's a tf function I can insert the trans and rot arrays into.

Thanks for your help

My code is pasted below:

import rospy
import tf
import numpy
from sensor_msgs.msg import PointCloud
import time


class pointcloudlistener():
    def __init__(self):
        rospy.init_node('cloudgrabber')
        self.listener=tf.TransformListener()
        self.listener.waitForTransform('/map', '/laser_frame', rospy.Time(0), rospy.Duration(4.0))        
        pclistener=rospy.Subscriber('/slam_cloud', PointCloud, self.cloudcallback, queue_size=1)
        self.pointlist=[]
        time.sleep(3)
        while len(rospy.get_published_topics())>2:
            time.sleep(1)



        f=open("pointcloudfile.xyz", "w")
        for i in self.pointlist:
            message=str(i.x)+str(" ")+ str(i.y)+ str(" ")+ str(i.z)+str("\n")
            f.writelines(message)
        f.close()        

    def cloudcallback(self,pointcloud):
        trans, rot= self.listener.lookupTransform('/map', '/laser_frame', rospy.Time(0))
        transformedcloud=self.listener.transformPointCloud('/map', pointcloud)

        for i in transformedcloud.points:
            self.pointlist.append(i)

pointcloudlistener()
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2021-05-21 13:47:07 -0500

tfoote gravatar image

This is a classic instance of where the transforms are lagging just slightly behind the data arriving. If you ask for TIme(0) you will get the "latest" complete transform(it will be off by the 40th of a second you've identified), and not the transform at the time of the data. For low rate systems that can work but there are much better solutions.

The simplest is to wait for the transform using waitForTransform. This is ok when your writing a script or something else that's low bandwidth and doesn't care much about latency.

But the best solution is to use a MessageFilter which will hold the data until the transform is available and then give you the callback.

http://wiki.ros.org/tf2/Tutorials/Usi...

There isn't one built into the python API but you can follow an example like this one: https://answers.ros.org/question/4906...

edit flag offensive delete link more

Comments

Thank you very much for this: I've managed to get it all working and extract the data! Thanks for your help

gnomezone gravatar image gnomezone  ( 2021-05-25 08:51:45 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-05-21 06:15:16 -0500

Seen: 237 times

Last updated: May 21 '21