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/io/io.h>
00052 #include <pcl/io/pcd_io.h>
00053 #include <pcl_conversions/pcl_conversions.h>
00054 #include "pcl_ros/transforms.h"
00055 #include <tf/transform_listener.h>
00056 #include <tf/transform_broadcaster.h>
00057
00058 typedef sensor_msgs::PointCloud2 PointCloud;
00059 typedef PointCloud::Ptr PointCloudPtr;
00060 typedef PointCloud::ConstPtr PointCloudConstPtr;
00061
00062
00063 int
00064 main (int argc, char** argv)
00065 {
00066 ros::init (argc, argv, "bag_to_pcd");
00067 if (argc < 4)
00068 {
00069 std::cerr << "Syntax is: " << argv[0] << " <file_in.bag> <topic> <output_directory>" << std::endl;
00070 std::cerr << "Example: " << argv[0] << " data.bag /laser_tilt_cloud ./pointclouds" << std::endl;
00071 return (-1);
00072 }
00073
00074
00075 tf::TransformListener tf_listener;
00076 tf::TransformBroadcaster tf_broadcaster;
00077
00078 rosbag::Bag bag;
00079 rosbag::View view;
00080 rosbag::View::iterator view_it;
00081
00082 try
00083 {
00084 bag.open (argv[1], rosbag::bagmode::Read);
00085 }
00086 catch (rosbag::BagException)
00087 {
00088 std::cerr << "Error opening file " << argv[1] << std::endl;
00089 return (-1);
00090 }
00091
00092 view.addQuery (bag, rosbag::TypeQuery ("sensor_msgs/PointCloud2"));
00093 view.addQuery (bag, rosbag::TypeQuery ("tf/tfMessage"));
00094 view.addQuery (bag, rosbag::TypeQuery ("tf2_msgs/TFMessage"));
00095 view_it = view.begin ();
00096
00097 std::string output_dir = std::string (argv[3]);
00098 boost::filesystem::path outpath (output_dir);
00099 if (!boost::filesystem::exists (outpath))
00100 {
00101 if (!boost::filesystem::create_directories (outpath))
00102 {
00103 std::cerr << "Error creating directory " << output_dir << std::endl;
00104 return (-1);
00105 }
00106 std::cerr << "Creating directory " << output_dir << std::endl;
00107 }
00108
00109
00110 std::cerr << "Saving recorded sensor_msgs::PointCloud2 messages on topic " << argv[2] << " to " << output_dir << std::endl;
00111
00112 PointCloud cloud_t;
00113 ros::Duration r (0.001);
00114
00115 while (view_it != view.end ())
00116 {
00117
00118 tf::tfMessage::ConstPtr tf = view_it->instantiate<tf::tfMessage> ();
00119 if (tf != NULL)
00120 {
00121 tf_broadcaster.sendTransform (tf->transforms);
00122 ros::spinOnce ();
00123 r.sleep ();
00124 }
00125 else
00126 {
00127
00128 PointCloudConstPtr cloud = view_it->instantiate<PointCloud> ();
00129 if (cloud == NULL)
00130 {
00131 ++view_it;
00132 continue;
00133 }
00134
00135
00136 if (!pcl_ros::transformPointCloud ("/base_link", *cloud, cloud_t, tf_listener))
00137 {
00138 ++view_it;
00139 continue;
00140 }
00141
00142 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;
00143
00144 std::stringstream ss;
00145 ss << output_dir << "/" << cloud_t.header.stamp << ".pcd";
00146 std::cerr << "Data saved to " << ss.str () << std::endl;
00147 pcl::io::savePCDFile (ss.str (), cloud_t, Eigen::Vector4f::Zero (),
00148 Eigen::Quaternionf::Identity (), true);
00149 }
00150
00151 ++view_it;
00152 }
00153
00154 return (0);
00155 }
00156