47 #include <boost/filesystem.hpp> 
   61   main (
int argc, 
char** argv)
 
   66     std::cerr << 
"Syntax is: " << argv[0] << 
" <file_in.bag> <topic> <output_directory> [<target_frame>]" << std::endl;
 
   67     std::cerr << 
"Example: " << argv[0] << 
" data.bag /laser_tilt_cloud ./pointclouds /base_link" << std::endl;
 
   85     std::cerr << 
"Error opening file " << argv[1] << std::endl;
 
   91   std::string target_topic;
 
   92   std::map<std::string, std::string> topic_list;
 
   95       topic_list[ci->topic] = ci->datatype;
 
   96       if (ci->topic == argv[2])
 
   98                   if (ci->datatype == std::string(
"sensor_msgs/PointCloud2"))
 
  100                           target_topic = std::string (argv[2]);
 
  105                           std::cerr << 
"Provided topic '" << argv[2] << 
"' is in the bag file, but is not of type sensor_msgs/PointCloud2 (type: " << ci->datatype << 
")" << std::endl;
 
  109   if (target_topic.empty())
 
  111       std::cerr << 
"Could not find a sensor_msgs/PointCloud2 type on topic '" << argv[2] << 
"' in bag file " << argv[1] << std::endl;
 
  112       std::cerr << 
"Topics found in the bag file:" << std::endl;
 
  113       for (std::map<std::string, std::string>::iterator it=topic_list.begin(); it!=topic_list.end(); ++it)
 
  114           std::cout << 
"    " << it->first << 
" (" << it->second << 
")" << std::endl;
 
  120   view_it = view.
begin ();
 
  122   std::string output_dir = std::string (argv[3]);
 
  123   boost::filesystem::path outpath (output_dir);
 
  124   if (!boost::filesystem::exists (outpath))
 
  126     if (!boost::filesystem::create_directories (outpath))
 
  128       std::cerr << 
"Error creating directory " << output_dir << std::endl;
 
  131     std::cerr << 
"Creating directory " << output_dir << std::endl;
 
  135   std::cerr << 
"Saving recorded sensor_msgs::PointCloud2 messages on topic " << target_topic << 
" to " << output_dir << std::endl;
 
  140   while (view_it != view.
end ())
 
  143     tf::tfMessage::ConstPtr 
tf = view_it->instantiate<tf::tfMessage> ();
 
  176       std::cerr << 
"Got " << cloud_t.width * cloud_t.height << 
" data points in frame " << cloud_t.header.frame_id << 
" on topic " << view_it->getTopic() << 
" with the following fields: " << 
pcl::getFieldsList (cloud_t) << std::endl;
 
  178       std::stringstream ss;
 
  179       ss << output_dir << 
"/" << cloud_t.header.stamp << 
".pcd";
 
  180       std::cerr << 
"Data saved to " << ss.str () << std::endl;
 
  182                             Eigen::Quaternionf::Identity (), 
true);