Go to the documentation of this file.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
00038
00039 #include <ros/ros.h>
00040
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
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
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