bag_to_pcd: check return code of transformPointCloud()
This fixes a bug where bag_to_pcd segfaults because of an ignored tf::ExtrapolationException.
This commit is contained in:
parent
fa2baa5248
commit
1a8f70b099
@ -129,8 +129,13 @@ int
|
|||||||
++view_it;
|
++view_it;
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Transform it
|
// Transform it
|
||||||
pcl_ros::transformPointCloud ("/base_link", *cloud, cloud_t, tf_listener);
|
if (!pcl_ros::transformPointCloud ("/base_link", *cloud, cloud_t, tf_listener))
|
||||||
|
{
|
||||||
|
++view_it;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
std::cerr << "Got " << cloud_t.width * cloud_t.height << " data points in frame " << cloud_t.header.frame_id << " with the following fields: " << pcl::getFieldsList (cloud_t) << std::endl;
|
std::cerr << "Got " << cloud_t.width * cloud_t.height << " data points in frame " << cloud_t.header.frame_id << " with the following fields: " << pcl::getFieldsList (cloud_t) << std::endl;
|
||||||
|
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user