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 public: 00060 string cloud_topic_; 00061 00062 ros::Subscriber sub_; 00063 00065 // Callback 00066 void 00067 cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud) 00068 { 00069 if ((cloud->width * cloud->height) == 0) 00070 return; 00071 00072 ROS_INFO ("Received %d data points in frame %s with the following fields: %s", (int)cloud->width * cloud->height, cloud->header.frame_id.c_str (), pcl::getFieldsList (*cloud).c_str ()); 00073 00074 std::stringstream ss; 00075 // Check if there is a parameter on the server that sets the prefix for the output file 00076 std::string prefix; 00077 nh_.getParam ("prefix", prefix); 00078 00079 ss << prefix << cloud->header.stamp << ".pcd"; 00080 ROS_INFO ("Data saved to %s", ss.str ().c_str ()); 00081 00082 pcl::io::savePCDFile (ss.str (), *cloud, Eigen::Vector4f::Zero (), 00083 Eigen::Quaternionf::Identity (), true); 00084 } 00085 00087 PointCloudToPCD () 00088 { 00089 cloud_topic_ = "input"; 00090 00091 sub_ = nh_.subscribe (cloud_topic_, 1, &PointCloudToPCD::cloud_cb, this); 00092 ROS_INFO ("Listening for incoming data on topic %s", nh_.resolveName (cloud_topic_).c_str ()); 00093 } 00094 }; 00095 00096 /* ---[ */ 00097 int 00098 main (int argc, char** argv) 00099 { 00100 ros::init (argc, argv, "pointcloud_to_pcd", ros::init_options::AnonymousName); 00101 00102 PointCloudToPCD b; 00103 ros::spin (); 00104 00105 return (0); 00106 } 00107 /* ]--- */