From 1a8f70b099d3c8024a3be22e46b378c9942b795a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Martin=20G=C3=BCnther?= Date: Wed, 19 Jun 2013 17:38:31 +0200 Subject: [PATCH] bag_to_pcd: check return code of transformPointCloud() This fixes a bug where bag_to_pcd segfaults because of an ignored tf::ExtrapolationException. --- pcl_ros/tools/bag_to_pcd.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/pcl_ros/tools/bag_to_pcd.cpp b/pcl_ros/tools/bag_to_pcd.cpp index eefb185f..f66d74b5 100644 --- a/pcl_ros/tools/bag_to_pcd.cpp +++ b/pcl_ros/tools/bag_to_pcd.cpp @@ -129,8 +129,13 @@ int ++view_it; continue; } + // 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;