extract_indices_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, 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 
36 #define BOOST_PARAMETER_MAX_ARITY 7
39 
40 #if PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 8
41 #include <pcl/filters/extract_indices.h>
42 #else
44 #endif
46 #include <sensor_msgs/PointCloud2.h>
47 
48 namespace jsk_pcl_ros
49 {
51  {
52  DiagnosticNodelet::onInit();
53  pnh_->param("keep_organized", keep_organized_, false);
54  pnh_->param("negative", negative_, false);
55  pnh_->param("max_queue_size", max_queue_size_, 10);
56  pnh_->param("approximate_sync", approximate_sync_, false);
57  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
59  }
60 
62  {
65  if (approximate_sync_) {
66  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(100);
67  async_->connectInput(sub_indices_, sub_cloud_);
68  async_->registerCallback(
69  boost::bind(&ExtractIndices::convert, this, _1, _2));
70  }
71  else {
72  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
73  sync_->connectInput(sub_indices_, sub_cloud_);
74  sync_->registerCallback(
75  boost::bind(&ExtractIndices::convert, this, _1, _2));
76  }
77  }
78 
80  {
83  }
84 
86  const PCLIndicesMsg::ConstPtr& indices_msg,
87  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
88  {
89  vital_checker_->poke();
90 
91  pcl::PCLPointCloud2::Ptr input(new pcl::PCLPointCloud2);
92  pcl_conversions::toPCL(*cloud_msg, *input);
93  pcl::PointIndices::Ptr indices (new pcl::PointIndices ());
94  pcl_conversions::toPCL(*indices_msg, *indices);
95 
96  // extract pointcloud with indices
97  pcl::ExtractIndices<pcl::PCLPointCloud2> extract;
98  extract.setInputCloud(input);
99  extract.setIndices(indices);
100  extract.setKeepOrganized(keep_organized_);
101  extract.setNegative(negative_);
102  pcl::PCLPointCloud2 output;
103  extract.filter(output);
104 
105  sensor_msgs::PointCloud2 out_cloud_msg;
106 #if PCL_MAJOR_VERSION <= 1 && PCL_MINOR_VERSION < 8
107  if (indices_msg->indices.empty() || cloud_msg->data.empty()) {
108  out_cloud_msg.height = cloud_msg->height;
109  out_cloud_msg.width = cloud_msg->width;
110  }
111 #endif
112  pcl_conversions::moveFromPCL(output, out_cloud_msg);
113 
114  out_cloud_msg.header = cloud_msg->header;
115  pub_.publish(out_cloud_msg);
116  }
117 }
118 
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ExtractIndices, nodelet::Nodelet)
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
message_filters::Subscriber< PCLIndicesMsg > sub_indices_
void toPCL(const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
void output(int index, double value)
boost::shared_ptr< ros::NodeHandle > pnh_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
jsk_topic_tools::VitalChecker::Ptr vital_checker_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
virtual void convert(const PCLIndicesMsg::ConstPtr &indices_msg, const sensor_msgs::PointCloud2::ConstPtr &msg)
void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46