pointcloud_to_pcd.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * $Id: pointcloud_to_pcd.cpp 33238 2010-03-11 00:46:58Z rusu $
35  *
36  */
37 
38 // ROS core
39 #include <ros/ros.h>
40 
41 #include <sensor_msgs/PointCloud2.h>
42 
43 #include <tf2_ros/buffer.h>
45 #include <tf2_eigen/tf2_eigen.h>
46 
47 // PCL includes
48 #include <pcl/io/io.h>
49 #include <pcl/io/pcd_io.h>
50 #include <pcl/point_types.h>
51 
53 
54 #include <Eigen/Geometry>
55 
56 using namespace std;
57 
66 {
67  protected:
69 
70  private:
71  std::string prefix_;
72  bool binary_;
74  std::string fixed_frame_;
77 
78  public:
79  string cloud_topic_;
80 
82 
84  // Callback
85  void
86  cloud_cb (const pcl::PCLPointCloud2::ConstPtr& cloud)
87  {
88  if ((cloud->width * cloud->height) == 0)
89  return;
90 
91  ROS_INFO ("Received %d data points in frame %s with the following fields: %s",
92  (int)cloud->width * cloud->height,
93  cloud->header.frame_id.c_str (),
94  pcl::getFieldsList (*cloud).c_str ());
95 
96  Eigen::Vector4f v = Eigen::Vector4f::Zero ();
97  Eigen::Quaternionf q = Eigen::Quaternionf::Identity ();
98  if (!fixed_frame_.empty ()) {
99  if (!tf_buffer_.canTransform (fixed_frame_, cloud->header.frame_id, pcl_conversions::fromPCL (cloud->header.stamp), ros::Duration (3.0))) {
100  ROS_WARN("Could not get transform!");
101  return;
102  }
103 
104  Eigen::Affine3d transform;
105  transform = tf2::transformToEigen (tf_buffer_.lookupTransform (fixed_frame_, cloud->header.frame_id, pcl_conversions::fromPCL (cloud->header.stamp)));
106  v = Eigen::Vector4f::Zero ();
107  v.head<3> () = transform.translation ().cast<float> ();
108  q = transform.rotation ().cast<float> ();
109  }
110 
111  std::stringstream ss;
112  ss << prefix_ << cloud->header.stamp << ".pcd";
113  ROS_INFO ("Data saved to %s", ss.str ().c_str ());
114 
115  pcl::PCDWriter writer;
116  if(binary_)
117  {
118  if(compressed_)
119  {
120  writer.writeBinaryCompressed (ss.str (), *cloud, v, q);
121  }
122  else
123  {
124  writer.writeBinary (ss.str (), *cloud, v, q);
125  }
126  }
127  else
128  {
129  writer.writeASCII (ss.str (), *cloud, v, q, 8);
130  }
131 
132  }
133 
135  PointCloudToPCD () : binary_(false), compressed_(false), tf_listener_(tf_buffer_)
136  {
137  // Check if a prefix parameter is defined for output file names.
138  ros::NodeHandle priv_nh("~");
139  if (priv_nh.getParam ("prefix", prefix_))
140  {
141  ROS_INFO_STREAM ("PCD file prefix is: " << prefix_);
142  }
143  else if (nh_.getParam ("prefix", prefix_))
144  {
145  ROS_WARN_STREAM ("Non-private PCD prefix parameter is DEPRECATED: "
146  << prefix_);
147  }
148 
149  priv_nh.getParam ("fixed_frame", fixed_frame_);
150  priv_nh.getParam ("binary", binary_);
151  priv_nh.getParam ("compressed", compressed_);
152  if(binary_)
153  {
154  if(compressed_)
155  {
156  ROS_INFO_STREAM ("Saving as binary compressed PCD");
157  }
158  else
159  {
160  ROS_INFO_STREAM ("Saving as binary PCD");
161  }
162  }
163  else
164  {
165  ROS_INFO_STREAM ("Saving as binary PCD");
166  }
167 
168  cloud_topic_ = "input";
169 
170  sub_ = nh_.subscribe (cloud_topic_, 1, &PointCloudToPCD::cloud_cb, this);
171  ROS_INFO ("Listening for incoming data on topic %s",
172  nh_.resolveName (cloud_topic_).c_str ());
173  }
174 };
175 
176 /* ---[ */
177 int
178  main (int argc, char** argv)
179 {
180  ros::init (argc, argv, "pointcloud_to_pcd", ros::init_options::AnonymousName);
181 
182  PointCloudToPCD b;
183  ros::spin ();
184 
185  return (0);
186 }
187 /* ]--- */
void cloud_cb(const pcl::PCLPointCloud2::ConstPtr &cloud)
pcl_ros::PCDWriter PCDWriter
Definition: pcd_io.cpp:179
std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
ros::Subscriber sub_
std::string fixed_frame_
tf2_ros::Buffer tf_buffer_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string resolveName(const std::string &name, bool remap=true) const
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_WARN(...)
ROSCPP_DECL void spin(Spinner &spinner)
ros::NodeHandle nh_
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
int main(int argc, char **argv)
#define ROS_INFO(...)
#define ROS_WARN_STREAM(args)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const
tf2_ros::TransformListener tf_listener_
Eigen::Isometry3d transformToEigen(const geometry_msgs::Transform &t)


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Wed Jun 5 2019 19:52:52