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

Not being able to lookup transform leading to node's death in building point cloud

asked 2012-01-24 20:57:33 -0500

alfa_80 gravatar image

updated 2012-01-25 01:45:08 -0500

I've been trying to build a point cloud using pose information. The code snippet for that is as below:

static tf::TransformBroadcaster tfb;
tf::Transform xform;
xform.setOrigin(tf::Vector3(pose3D_LD2.pose.position.x, pose3D_LD2.pose.position.y, pose3D_LD2.pose.position.z));
xform.setRotation(tf::Quaternion(previous_poseLD_.pose.orientation.x, previous_poseLD_.pose.orientation.y, previous_poseLD_.pose.orientation.z, previous_poseLD_.pose.orientation.w));
tfb.sendTransform(tf::StampedTransform(xform, ros::Time(pose3D_LD2.header.stamp), "/base_link", "/laser"));
tfListener_.waitForTransform("/base_link", "/laser", ros::Time(0), ros::Duration(2.0));
projector_.transformLaserScanToPointCloud("/base_link", previous_scan_, cloud, tfListener_);

However, I receive this error message:

terminate called after throwing an instance of 'tf::ExtrapolationException'
what():  Unable to lookup transform, cache is empty, when looking up transform from frame [/laser] to frame [/base_link]
[pointcloud_builder_node-5] process has died [pid 13012, exit code -6].

what could be the error that leads to the death of the node as stated in the error message? Or am I missing something?

Thanks in advance.

EDIT: I've also tried to comment last 2 lines of the above code snippet which are disabling waitForTransform and transformLaserScanToPointCloud calls, and watching the output up to calling sendTransform. It gives a warning like below:

[ WARN] [1327489676.295791909]: TF_OLD_DATA ignoring data from the past for frame /laser at time 24.279 according to authority /pointcloud_builder_node
Possible reasons are listed at 
[ WARN] [1327489676.628911299]: TF_OLD_DATA ignoring data from the past for frame /laser at time 24.328 according to authority /pointcloud_builder_node
Possible reasons are listed at 
[ WARN] [1327489676.962231439]: TF_OLD_DATA ignoring data from the past for frame /laser at time 24.348 according to authority /pointcloud_builder_node
Possible reasons are listed at

Any remedy for this kind of error?

UPDATE:

static tf::TransformBroadcaster tfb;
tf::Transform xform;
xform.setOrigin(tf::Vector3(pose3D_LD2.pose.position.x, pose3D_LD2.pose.position.y, pose3D_LD2.pose.position.z));
xform.setRotation(tf::Quaternion(previous_poseLD_.pose.orientation.x, previous_poseLD_.pose.orientation.y, previous_poseLD_.pose.orientation.z, previous_poseLD_.pose.orientation.w));
tfb.sendTransform(tf::StampedTransform(xform, ros::Time(pose3D_LD2.header.stamp), "base_link", "laser"));
tfListener_.waitForTransform("base_link", "laser", previous_scan_.header.stamp, ros::Duration(2.0));
projector_.transformLaserScanToPointCloud("base_link", previous_scan_, cloud, tfListener_);
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
4

answered 2012-01-24 21:38:55 -0500

Lorenz gravatar image

updated 2012-01-24 22:16:04 -0500

Where is your point cloud coming from? If it is a rosbag, try setting the parameter use_sim_time to true and playing it back with rosbag play --clock <bag>. If it's an actual sensor, is it maybe connected to a different computer and the clocks are not synchronized?

Another, more dirty solution would be to set previous_scan_.header.stamp to ros::Time::now(). Also, make sure that pose3D_LD2.header.stamp and previous_scan_.header.stamp are equal. If not, you need at least two transforms, one before the stamp of your scan and one after it. TF needs to do interpolation if it doesn't have an exact time stamp for which it needs two transforms.

Btw. your waitForTransform call shouldn't use ros::Time(0) but previous_scan_.header.stamp.

edit flag offensive delete link more

Comments

1
Thanks a lot Lorenz, that works for this problem. However, the point cloud is not working yet. Your last line saved me.
alfa_80 gravatar image alfa_80  ( 2012-01-24 22:54:36 -0500 )edit
@Lorenz: The follow-up question is here if you can guide me on this: http://answers.ros.org/question/3715/cloud-values-are-not-loaded
alfa_80 gravatar image alfa_80  ( 2012-01-24 23:13:34 -0500 )edit
After editing some lines of code, I've again obtained this kind of error.
alfa_80 gravatar image alfa_80  ( 2012-01-25 01:00:24 -0500 )edit
I'm again trying to revert but still not getting it..
alfa_80 gravatar image alfa_80  ( 2012-01-25 01:00:57 -0500 )edit
This time, up to waitForTransform, it returns no error, but when it comes to transformLaserScanToPointCloud call, then, it's dead.
alfa_80 gravatar image alfa_80  ( 2012-01-25 01:06:43 -0500 )edit
Note that you don't actually check if waitForTransform actually succeeded. In your call with timeout 2 seconds, it will return false if no transform could be found. In that case, transformlaserScanToPointCloud will fail.
Lorenz gravatar image Lorenz  ( 2012-01-25 01:15:37 -0500 )edit
Do you mean, I should increase it, instead of using 2 seconds?
alfa_80 gravatar image alfa_80  ( 2012-01-25 01:19:58 -0500 )edit
Just do something like: if (!waitForTransform(...)) { ROS_ERROR("Unable to transform"); } else { projector_.transformLaserScanToPointCloud(...); } to prevent the exception. Increasing the timeout will probably not help. Make sure that the time stamps of previous_scan_ and pose3D_LD2 are equal.
Lorenz gravatar image Lorenz  ( 2012-01-25 01:24:06 -0500 )edit
2

answered 2012-01-25 01:42:28 -0500

DimitriProsser gravatar image

The problem is that you're not wrapping these functions:

tfListener_.waitForTransform("/base_link", "/laser", ros::Time(0), ros::Duration(2.0));
projector_.transformLaserScanToPointCloud("/base_link", previous_scan_, cloud, tfListener_);

in a try/catch block. Both of these operations throw a transform exception that you must catch. This will not solve the problem that is cause the exception, but it will prevent your program from exiting every time one is received. Try the following:

try
{
    tfListener_.waitForTransform("/base_link", "/laser", ros::Time(0), ros::Duration(2.0));
    projector_.transformLaserScanToPointCloud("/base_link", previous_scan_, cloud, tfListener_);
}
catch (tf::TransformException e)
{
    ROS_WARN("My_node: %s", ex.what());
}
edit flag offensive delete link more

Comments

@DimitriProsser: Thanks a lot..It's really a great help. But I still do not understand why these 2 lines need to be in the try/catch block. As they are running sequentially, it should be OK, in my opinion. But your workaround is right here.
alfa_80 gravatar image alfa_80  ( 2012-01-25 02:33:53 -0500 )edit
Well, it's not quite a "workaround". All of ROS's tf lookup functions throw exceptions when they're not able to do perform the requested operation. In C++, if you fail to catch an exception, it will crash your program. Basically, you should always wrap tf lookups in a try/catch block.
DimitriProsser gravatar image DimitriProsser  ( 2012-01-25 02:43:12 -0500 )edit
Thanks a lot for the explanation. That answers why a lot of crashes I experienced before when dealing with the tf lookup functions.
alfa_80 gravatar image alfa_80  ( 2012-01-25 02:55:16 -0500 )edit
waitForTransform does _not_ throw tf exceptions according to the API docs. Only lookup functions throw TF exceptions. I would call this solution actually a workaround. It is not clear to me why sometimes waitForTransform seems to succeed while transformLaserScanToPointCloud fails.
Lorenz gravatar image Lorenz  ( 2012-01-25 04:12:28 -0500 )edit
My bad. But you can put the waitForTransform() call outside of the try/catch if you want to. It will work exactly the same way.
DimitriProsser gravatar image DimitriProsser  ( 2012-01-25 04:33:31 -0500 )edit
@Lorenz and @DimitriProsser: Could you point me to the API docs that shows those throwing exceptions..Any link.
alfa_80 gravatar image alfa_80  ( 2012-01-25 04:52:30 -0500 )edit
ros.org/wiki/tf for general documentation on tf. The API docs as well as tutorials are then linked on the right.
Lorenz gravatar image Lorenz  ( 2012-01-25 04:58:39 -0500 )edit
Thanks anyway..
alfa_80 gravatar image alfa_80  ( 2012-01-25 10:02:40 -0500 )edit

Question Tools

Stats

Asked: 2012-01-24 20:57:33 -0500

Seen: 3,172 times

Last updated: Jan 25 '12