bag_to_pcd.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: bag_to_pcd.cpp 34671 2010-12-12 01:28:36Z rusu $
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   // TF
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   //view.addQuery (bag, rosbag::TypeQuery ("sensor_msgs/PointCloud2"));
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   // Add the PointCloud2 handler
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   // Loop over the whole bag file
00117   while (view_it != view.end ())
00118   {
00119         try{
00120                 // Handle TF messages first
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                   // Get the PointCloud2 message
00131                   PointCloudConstPtr cloud = view_it->instantiate<PointCloud> ();
00132                   if (cloud == NULL)
00133                   {
00134                         ++view_it;
00135                         continue;
00136                   }
00137                   // Transform it
00138                   tf::StampedTransform transform;
00139                         //if(argv[4] != cloud->header.frame_id)
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                   //pcl_ros::transformPointCloud ("/head_axis_link", *cloud, cloud_t, tf_listener);
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     // Increment the iterator
00161     ++view_it;
00162   }
00163 
00164   return (0);
00165 }
00166 /* ]--- */


cob_3d_mapping_tools
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:04:26