Adding target_frame

[Ability to specify frame in bag_to_pcd #55](https://github.com/ros-perception/perception_pcl/issues/55)
This commit is contained in:
Ruffin 2014-10-18 17:59:47 -04:00 committed by Paul Bovbel
parent 155a69e484
commit ac5593dd7c

View File

@ -66,8 +66,8 @@ int
ros::init (argc, argv, "bag_to_pcd"); ros::init (argc, argv, "bag_to_pcd");
if (argc < 4) if (argc < 4)
{ {
std::cerr << "Syntax is: " << argv[0] << " <file_in.bag> <topic> <output_directory>" << std::endl; std::cerr << "Syntax is: " << argv[0] << " <file_in.bag> <topic> <output_directory> [<target_frame>]" << std::endl;
std::cerr << "Example: " << argv[0] << " data.bag /laser_tilt_cloud ./pointclouds" << std::endl; std::cerr << "Example: " << argv[0] << " data.bag /laser_tilt_cloud ./pointclouds /base_link" << std::endl;
return (-1); return (-1);
} }
@ -132,12 +132,21 @@ int
continue; continue;
} }
// If a target_frame was specified
if(argc > 4)
{
// Transform it // Transform it
if (!pcl_ros::transformPointCloud ("/base_link", *cloud, cloud_t, tf_listener)) if (!pcl_ros::transformPointCloud (argv[4], *cloud, cloud_t, tf_listener))
{ {
++view_it; ++view_it;
continue; continue;
} }
}
else
{
// Else, don't transform it
cloud_t = *cloud;
}
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;