pointcloud_to_pcd_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
37 #include <sensor_msgs/PointCloud2.h>
40 
41 
42 #include <pcl/io/io.h>
43 #include <Eigen/Geometry>
44 
45 namespace jsk_pcl_ros_utils
46 {
48  {
49  timer_.stop();
50  }
51 
53  {
54  pcl::PCLPointCloud2::ConstPtr cloud;
55  cloud = ros::topic::waitForMessage<pcl::PCLPointCloud2>("input", *pnh_);
56  if ((cloud->width * cloud->height) == 0)
57  {
58  return;
59  }
60 
61  ROS_INFO ("Received %d data points in frame %s with the following fields: %s",
62  (int)cloud->width * cloud->height,
63  cloud->header.frame_id.c_str (),
64  pcl::getFieldsList (*cloud).c_str ());
65 
66  Eigen::Vector4f v = Eigen::Vector4f::Zero ();
67  Eigen::Quaternionf q = Eigen::Quaternionf::Identity ();
68  if (!fixed_frame_.empty ()) {
69  if (!tf_listener_->waitForTransform (fixed_frame_, cloud->header.frame_id, pcl_conversions::fromPCL (cloud->header).stamp, ros::Duration (duration_))) {
70  ROS_WARN("Could not get transform!");
71  return;
72  }
73  tf::StampedTransform transform_stamped;
74  tf_listener_->lookupTransform (fixed_frame_, cloud->header.frame_id, pcl_conversions::fromPCL (cloud->header).stamp, transform_stamped);
75  Eigen::Affine3d transform;
76  tf::transformTFToEigen(transform_stamped, transform);
77  v = Eigen::Vector4f::Zero ();
78  v.head<3> () = transform.translation ().cast<float> ();
79  q = transform.rotation ().cast<float> ();
80  }
81 
82  std::stringstream ss;
83  ss << prefix_ << cloud->header.stamp << ".pcd";
84  ROS_INFO ("Data saved to %s", ss.str ().c_str ());
85 
86  pcl::PCDWriter writer;
87  if(binary_)
88  {
89  if(compressed_)
90  {
91  writer.writeBinaryCompressed (ss.str (), *cloud, v, q);
92  }
93  else
94  {
95  writer.writeBinary (ss.str (), *cloud, v, q);
96  }
97  }
98  else
99  {
100  writer.writeASCII (ss.str (), *cloud, v, q, 8);
101  }
102  }
103 
105  {
106  PCLNodelet::onInit();
107  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
108  dynamic_reconfigure::Server<Config>::CallbackType f = boost::bind(&PointCloudToPCD::configCallback, this, _1, _2);
109  srv_->setCallback (f);
111  if(binary_)
112  {
113  if(compressed_)
114  {
115  ROS_INFO_STREAM ("Saving as binary compressed PCD");
116  }
117  else
118  {
119  ROS_INFO_STREAM ("Saving as binary PCD");
120  }
121  }
122  else
123  {
124  ROS_INFO_STREAM ("Saving as binary PCD");
125  }
126  }
127 
128  void PointCloudToPCD::configCallback(Config &config, uint32_t level)
129  {
130  boost::mutex::scoped_lock lock(mutex_);
131  prefix_ = config.prefix;
132  binary_ = config.binary;
133  compressed_ = config.compressed;
134  fixed_frame_ = config.fixed_frame;
135  duration_ = config.duration;
136  timer_ = pnh_->createTimer(ros::Duration(duration_), boost::bind(&PointCloudToPCD::timerCallback, this, _1));
137  }
138 }
139 
f
lock
std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
void stop()
#define ROS_WARN(...)
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
q
boost::shared_ptr< ros::NodeHandle > pnh_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PointCloudToPCD, nodelet::Nodelet)
#define ROS_INFO(...)
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
#define ROS_INFO_STREAM(args)
tf::TransformListener * tf_listener_
virtual void timerCallback(const ros::TimerEvent &event)
static tf::TransformListener * getInstance()
virtual void configCallback(Config &config, uint32_t level)
std_msgs::Header fromPCL(const pcl::PCLHeader &pcl_header)


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15