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

bag file and tf transformation

asked 2019-09-20 04:38:01 -0500

Jad gravatar image

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
edit retag flag offensive close merge delete

Comments

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.

gvdhoorn gravatar image gvdhoorn  ( 2019-09-20 06:22:14 -0500 )edit

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 ?

Jad gravatar image Jad  ( 2019-09-20 07:12:57 -0500 )edit

my bag is really big about 193.358534 sec

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.

how to increase it ?

The Python API of Buffer, mirrors the C++ one.

You can use the cache_time argument of the Buffer ctor. See tf2_ros::Buffer::Buffer(..).

gvdhoorn gravatar image gvdhoorn  ( 2019-09-20 07:20:27 -0500 )edit

I did do this :

self._tf_buffer = tf2_ros.Buffer(cache_time=rospy.Duration(20000))

but i am still getting :

g2o_file_generator:43: UserWarning: translation should be of type Vector3
  self._tf_buffer.set_transform(msg_tf,'default_authority')
g2o_file_generator:43: UserWarning: rotation should be of type Quaternion
  self._tf_buffer.set_transform(msg_tf,'default_authority')
[WARN][/G2O_Generator][1568982844.054444]: Lookup would require extrapolation at time 1568786441.083348989, but only time 1568785834.687333107 is in the buffer, when looking up transform from frame [nav350] to frame [odom]
Jad gravatar image Jad  ( 2019-09-20 07:36:07 -0500 )edit

Am I doing something wrong in my code ?

Jad gravatar image Jad  ( 2019-09-20 07:37:16 -0500 )edit

The UserWarning messages are certainly not what I would expect.

I would check that you're feeding the buffer with the correct data types.

gvdhoorn gravatar image gvdhoorn  ( 2019-09-20 08:31:34 -0500 )edit

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 ?

Jad gravatar image Jad  ( 2019-09-20 08:56:56 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2019-10-02 07:13:18 -0500

Jad gravatar image

this could be solved like this :

tf_buffer = tf2_py.BufferCore(rospy.Duration(1000000))
bag = rosbag.Bag(bag)
for topic, msg, t in bag.read_messages(topics=['/tf', '/tf_static']):
    for msg_tf in msg.transforms:
        if topic == '/tf_static':
            tf_buffer.set_transform_static(msg_tf, "default_authority")
        else:
            tf_buffer.set_transform(msg_tf, "default_authority")
return tf_buffer
edit flag offensive delete link more

Comments

Note, in Melodic, BufferCore doesn't have a lookup_transform method. Instead it is named tf_buffer.lookup_transform_core().

hansolo gravatar image hansolo  ( 2020-06-02 09:06:21 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2019-09-20 04:38:01 -0500

Seen: 3,504 times

Last updated: Oct 02 '19