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