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_);
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.
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());
}
Asked: 2012-01-25 02:57:33 -0500
Seen: 1,189 times
Last updated: Jan 25 '12
transform Laser Scan To PointCloud
Function for unpacking RGB point field from point in point cloud?
How to know which points pcl::PassThrough and pcl::StatisticalOutlierRemoval removes?
How to change the Kinect point cloud resolution
How to display the Kinect point cloud using image colours?
pointcloud_to_laserscan height range
template instantiation problems with new point types
How to transform a point cloud from camera coordinates to world coordinates
ROS Answers is licensed under Creative Commons Attribution 3.0 Content on this site is licensed under a Creative Commons Attribution Share Alike 3.0 license.