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 <sensor_msgs/PointCloud2.h>
00042
00043 #include <tf2_ros/buffer.h>
00044 #include <tf2_ros/transform_listener.h>
00045 #include <tf2_eigen/tf2_eigen.h>
00046
00047
00048 #include <pcl/io/io.h>
00049 #include <pcl/io/pcd_io.h>
00050 #include <pcl/point_types.h>
00051
00052 #include <pcl_conversions/pcl_conversions.h>
00053
00054 #include <Eigen/Geometry>
00055
00056 using namespace std;
00057
00065 class PointCloudToPCD
00066 {
00067 protected:
00068 ros::NodeHandle nh_;
00069
00070 private:
00071 std::string prefix_;
00072 bool binary_;
00073 bool compressed_;
00074 std::string fixed_frame_;
00075 tf2_ros::Buffer tf_buffer_;
00076 tf2_ros::TransformListener tf_listener_;
00077
00078 public:
00079 string cloud_topic_;
00080
00081 ros::Subscriber sub_;
00082
00084
00085 void
00086 cloud_cb (const pcl::PCLPointCloud2::ConstPtr& cloud)
00087 {
00088 if ((cloud->width * cloud->height) == 0)
00089 return;
00090
00091 ROS_INFO ("Received %d data points in frame %s with the following fields: %s",
00092 (int)cloud->width * cloud->height,
00093 cloud->header.frame_id.c_str (),
00094 pcl::getFieldsList (*cloud).c_str ());
00095
00096 Eigen::Vector4f v = Eigen::Vector4f::Zero ();
00097 Eigen::Quaternionf q = Eigen::Quaternionf::Identity ();
00098 if (!fixed_frame_.empty ()) {
00099 if (!tf_buffer_.canTransform (fixed_frame_, cloud->header.frame_id, pcl_conversions::fromPCL (cloud->header.stamp), ros::Duration (3.0))) {
00100 ROS_WARN("Could not get transform!");
00101 return;
00102 }
00103
00104 Eigen::Affine3d transform;
00105 transform = tf2::transformToEigen (tf_buffer_.lookupTransform (fixed_frame_, cloud->header.frame_id, pcl_conversions::fromPCL (cloud->header.stamp)));
00106 v = Eigen::Vector4f::Zero ();
00107 v.head<3> () = transform.translation ().cast<float> ();
00108 q = transform.rotation ().cast<float> ();
00109 }
00110
00111 std::stringstream ss;
00112 ss << prefix_ << cloud->header.stamp << ".pcd";
00113 ROS_INFO ("Data saved to %s", ss.str ().c_str ());
00114
00115 pcl::PCDWriter writer;
00116 if(binary_)
00117 {
00118 if(compressed_)
00119 {
00120 writer.writeBinaryCompressed (ss.str (), *cloud, v, q);
00121 }
00122 else
00123 {
00124 writer.writeBinary (ss.str (), *cloud, v, q);
00125 }
00126 }
00127 else
00128 {
00129 writer.writeASCII (ss.str (), *cloud, v, q, 8);
00130 }
00131
00132 }
00133
00135 PointCloudToPCD () : binary_(false), compressed_(false), tf_listener_(tf_buffer_)
00136 {
00137
00138 ros::NodeHandle priv_nh("~");
00139 if (priv_nh.getParam ("prefix", prefix_))
00140 {
00141 ROS_INFO_STREAM ("PCD file prefix is: " << prefix_);
00142 }
00143 else if (nh_.getParam ("prefix", prefix_))
00144 {
00145 ROS_WARN_STREAM ("Non-private PCD prefix parameter is DEPRECATED: "
00146 << prefix_);
00147 }
00148
00149 priv_nh.getParam ("fixed_frame", fixed_frame_);
00150 priv_nh.getParam ("binary", binary_);
00151 priv_nh.getParam ("compressed", compressed_);
00152 if(binary_)
00153 {
00154 if(compressed_)
00155 {
00156 ROS_INFO_STREAM ("Saving as binary compressed PCD");
00157 }
00158 else
00159 {
00160 ROS_INFO_STREAM ("Saving as binary PCD");
00161 }
00162 }
00163 else
00164 {
00165 ROS_INFO_STREAM ("Saving as binary PCD");
00166 }
00167
00168 cloud_topic_ = "input";
00169
00170 sub_ = nh_.subscribe (cloud_topic_, 1, &PointCloudToPCD::cloud_cb, this);
00171 ROS_INFO ("Listening for incoming data on topic %s",
00172 nh_.resolveName (cloud_topic_).c_str ());
00173 }
00174 };
00175
00176
00177 int
00178 main (int argc, char** argv)
00179 {
00180 ros::init (argc, argv, "pointcloud_to_pcd", ros::init_options::AnonymousName);
00181
00182 PointCloudToPCD b;
00183 ros::spin ();
00184
00185 return (0);
00186 }
00187