bag file and tf transformation
HI,
I recorded a bag file of my robot and this bag file contains all the topics. From this data I need to transform messages from laser-scanner to odom frame using the time stamp when the bag created. What i did is I used the tf and tf_static topics and put them in a buffer and then tried to transform between frames but i am still getting an error :
[WARN][/G2O_Generator][1568971858.801114]: Lookup would require extrapolation into the past. Requested time 1568786441.083348989 but the earliest data is at time 1568786624.298866987, when looking up transform from frame [nav350] to frame [odom]
And this is the part of my code that does this :
import rospy
import rosbag
from world_model_conversions.sensor_msgs_conversions import vector_list_from_cloud_msg
import tf2_ros
import tf
import tf2_py as tf2
import numpy
from std_msgs.msg import Header
from tf2_geometry_msgs import PointStamped
from tf2_sensor_msgs.tf2_sensor_msgs import do_transform_cloud
from geometry_msgs.msg import Pose, Point, Quaternion
class G2O_Generator(object):
def __init__(self):
self._tf_buffer = tf2_ros.Buffer()
self._tf_listener = tf2_ros.TransformListener(self._tf_buffer)
def convert_pointcloud_frame(self, bag_name):
#fill the buffer with tf and tf_static msgs
bag = rosbag.Bag(bag_name)
for topic, msg, t in bag.read_messages(topics=['/tf', '/tf_static']):
for msg_tf in msg.transforms:
self._tf_buffer.set_transform(msg_tf,'default_authority')
bag = rosbag.Bag(bag_name)
for topic, msg, t in bag.read_messages(topics=['/reflector_cloud']):
reflector_cloud_msgs = msg
trans = self._tf_buffer.lookup_transform("odom", reflector_cloud_msgs.header.frame_id,
reflector_cloud_msgs.header.stamp,
rospy.Duration(1))
cloud_out = do_transform_cloud(reflector_cloud_msgs, trans)
print ("pint_cloud", cloud_out)
bag.close()
if __name__ == '__main__':
rospy.init_node('G2O_Generator')
m = G2O_Generator()
m.convert_pointcloud_f
If the bag is 'long' (ie: longer than 60 seconds), you may need to increase the length of the buffer.
Otherwise older transforms may have been pruned from your buffer before you get to the part of your script that actually tries to look them up.
thank you very much, actually my bag is really big about 193.358534 sec .. the question can the buffer be increased till that length ? if yes would you like to tell me how to increase it ?
that's only about 3.5 minutes. That's not really that long :). I have bags of several hours, and that is not even very long.
The Python API of
Buffer
, mirrors the C++ one.You can use the
cache_time
argument of theBuffer
ctor. See tf2_ros::Buffer::Buffer(..).I did do this :
but i am still getting :
Am I doing something wrong in my code ?
The
UserWarning
messages are certainly not what I would expect.I would check that you're feeding the buffer with the correct data types.
Actually i think i know what the problem is , /tf_static is static and it is initialized in the beginning in the bag that's why the timestamp is not correct, do you know how to solve this ?