Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00047 #include <sstream>
00048 #include <boost/filesystem.hpp>
00049 #include <rosbag/bag.h>
00050 #include <rosbag/view.h>
00051 #include <pcl/conversions.h>
00052 #include "pcl/io/io.h"
00053 #include "pcl/io/pcd_io.h"
00054 #include "pcl/conversions.h"
00055 #include "pcl_ros/transforms.h"
00056 #include <pcl_conversions/pcl_conversions.h>
00057 #include <tf/transform_listener.h>
00058 #include <tf/transform_broadcaster.h>
00059
00060 typedef sensor_msgs::PointCloud2 PointCloud;
00061 typedef PointCloud::Ptr PointCloudPtr;
00062 typedef PointCloud::ConstPtr PointCloudConstPtr;
00063
00064
00065 int
00066 main (int argc, char** argv)
00067 {
00068 ros::init (argc, argv, "bag_to_pcd");
00069 if (argc < 5)
00070 {
00071 std::cerr << "Syntax is: " << argv[0] << " <file_in.bag> <topic> <output_directory> <target_frame>" << std::endl;
00072 std::cerr << "Example: " << argv[0] << " data.bag /laser_tilt_cloud ./pointclouds /base_link" << std::endl;
00073 return (-1);
00074 }
00075
00076
00077 tf::TransformListener tf_listener;
00078 tf::TransformBroadcaster tf_broadcaster;
00079
00080 rosbag::Bag bag;
00081 rosbag::View view;
00082 rosbag::View::iterator view_it;
00083
00084 try
00085 {
00086 bag.open (argv[1], rosbag::bagmode::Read);
00087 }
00088 catch (rosbag::BagException)
00089 {
00090 std::cerr << "Error opening file " << argv[1] << std::endl;
00091 return (-1);
00092 }
00093
00094
00095 view.addQuery (bag, rosbag::TopicQuery(argv[2]));
00096 view.addQuery (bag, rosbag::TypeQuery ("tf/tfMessage"));
00097 view_it = view.begin ();
00098
00099 std::string output_dir = std::string (argv[3]);
00100 boost::filesystem::path outpath (output_dir);
00101 if (!boost::filesystem::exists (outpath))
00102 {
00103 if (!boost::filesystem::create_directories (outpath))
00104 {
00105 std::cerr << "Error creating directory " << output_dir << std::endl;
00106 return (-1);
00107 }
00108 std::cerr << "Creating directory " << output_dir << std::endl;
00109 }
00110
00111
00112 std::cerr << "Saving recorded sensor_msgs::PointCloud2 messages on topic " << argv[2] << " to " << output_dir << std::endl;
00113
00114 PointCloud cloud_t;
00115 ros::Duration r (0.001);
00116
00117 while (view_it != view.end ())
00118 {
00119 try{
00120
00121 tf::tfMessage::ConstPtr tf = view_it->instantiate<tf::tfMessage> ();
00122 if (tf != NULL)
00123 {
00124 tf_broadcaster.sendTransform (tf->transforms);
00125 ros::spinOnce ();
00126 r.sleep ();
00127 }
00128 else
00129 {
00130
00131 PointCloudConstPtr cloud = view_it->instantiate<PointCloud> ();
00132 if (cloud == NULL)
00133 {
00134 ++view_it;
00135 continue;
00136 }
00137
00138 tf::StampedTransform transform;
00139
00140 tf_listener.lookupTransform(cloud->header.frame_id, argv[4], cloud->header.stamp, transform);
00141 Eigen::Matrix4f out_mat;
00142 pcl_ros::transformAsMatrix (transform, out_mat);
00143
00144 pcl_ros::transformPointCloud (out_mat, *cloud, cloud_t);
00145 pcl::PCLPointCloud2 cloud_t2;
00146 pcl_conversions::toPCL(cloud_t, cloud_t2);
00147
00148 std::cerr << "Got " << cloud_t2.width * cloud_t2.height << " data points in frame " << cloud_t2.header.frame_id << " with the following fields: " << pcl::getFieldsList (cloud_t2) << std::endl;
00149
00150 std::stringstream ss;
00151 ss << output_dir << "/" << cloud_t2.header.stamp << ".pcd";
00152 std::cerr << "Data saved to " << ss.str () << std::endl;
00153 pcl::io::savePCDFile (ss.str (), cloud_t2, Eigen::Vector4f::Zero (),
00154 Eigen::Quaternionf::Identity (), false);
00155 }
00156 }
00157 catch (tf::TransformException ex){
00158 ROS_ERROR("%s",ex.what());
00159 }
00160
00161 ++view_it;
00162 }
00163
00164 return (0);
00165 }
00166