pointcloud_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: pointcloud_to_pcd.cpp 33238 2010-03-11 00:46:58Z rusu $
00035  *
00036  */
00037 
00038 // ROS core
00039 #include <ros/ros.h>
00040 // PCL includes
00041 #include <pcl/io/io.h>
00042 #include <pcl/io/pcd_io.h>
00043 #include <pcl/point_types.h>
00044 
00045 using namespace std;
00046 
00054 class PointCloudToPCD
00055 {
00056   protected:
00057     ros::NodeHandle nh_;
00058 
00059   private:
00060     std::string prefix_;
00061 
00062   public:
00063     string cloud_topic_;
00064 
00065     ros::Subscriber sub_;
00066 
00068     // Callback
00069     void
00070       cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud)
00071     {
00072       if ((cloud->width * cloud->height) == 0)
00073         return;
00074 
00075       ROS_INFO ("Received %d data points in frame %s with the following fields: %s",
00076                 (int)cloud->width * cloud->height,
00077                 cloud->header.frame_id.c_str (),
00078                 pcl::getFieldsList (*cloud).c_str ());
00079 
00080       std::stringstream ss;
00081       ss << prefix_ << cloud->header.stamp << ".pcd";
00082       ROS_INFO ("Data saved to %s", ss.str ().c_str ());
00083 
00084       pcl::io::savePCDFile (ss.str (), *cloud, Eigen::Vector4f::Zero (),
00085                             Eigen::Quaternionf::Identity (), false);
00086     }
00087 
00089     PointCloudToPCD ()
00090     {
00091       // Check if a prefix parameter is defined for output file names.
00092       ros::NodeHandle priv_nh("~");
00093       if (priv_nh.getParam ("prefix", prefix_))
00094         {
00095           ROS_INFO_STREAM ("PCD file prefix is: " << prefix_);
00096         }
00097       else if (nh_.getParam ("prefix", prefix_))
00098         {
00099           ROS_WARN_STREAM ("Non-private PCD prefix parameter is DEPRECATED: "
00100                            << prefix_);
00101         }
00102 
00103       cloud_topic_ = "input";
00104 
00105       sub_ = nh_.subscribe (cloud_topic_, 1,  &PointCloudToPCD::cloud_cb, this);
00106       ROS_INFO ("Listening for incoming data on topic %s",
00107                 nh_.resolveName (cloud_topic_).c_str ());
00108     }
00109 };
00110 
00111 /* ---[ */
00112 int
00113   main (int argc, char** argv)
00114 {
00115   ros::init (argc, argv, "pointcloud_to_pcd", ros::init_options::AnonymousName);
00116 
00117   PointCloudToPCD b;
00118   ros::spin ();
00119 
00120   return (0);
00121 }
00122 /* ]--- */


pcl_ros
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:22:23