subtract_point_indices_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/or 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
38 
39 
40 namespace jsk_pcl_ros_utils
41 {
43  {
44  DiagnosticNodelet::onInit();
45  pnh_->param("approximate_sync", approximate_sync_, false);
46  pub_ = advertise<PCLIndicesMsg>(*pnh_, "output", 1);
48  }
49 
51  {
52  sub_src1_.subscribe(*pnh_, "input/src1", 1);
53  sub_src2_.subscribe(*pnh_, "input/src2", 1);
54  if (approximate_sync_) {
55  async_ = boost::make_shared<message_filters::Synchronizer<ASyncPolicy> >(100);
56  async_->connectInput(sub_src1_, sub_src2_);
57  async_->registerCallback(
58  boost::bind(&SubtractPointIndices::subtract,
59  this, _1, _2));
60  }
61  else {
62  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
63  sync_->connectInput(sub_src1_, sub_src2_);
64  sync_->registerCallback(
65  boost::bind(&SubtractPointIndices::subtract,
66  this, _1, _2));
67  }
68  }
69 
71  {
74  }
75 
77  const PCLIndicesMsg::ConstPtr& src1,
78  const PCLIndicesMsg::ConstPtr& src2)
79  {
80  vital_checker_->poke();
81  pcl::PointIndices a, b;
82  pcl_conversions::toPCL(*src1, a);
83  pcl_conversions::toPCL(*src2, b);
84  pcl::PointIndices::Ptr c = jsk_recognition_utils::subIndices(a, b);
85  c->header = a.header;
86  PCLIndicesMsg ros_indices;
87  pcl_conversions::fromPCL(*c, ros_indices);
88  ros_indices.header = src1->header;
89  pub_.publish(ros_indices);
90  }
91 }
92 
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
message_filters::Subscriber< PCLIndicesMsg > sub_src2_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::SubtractPointIndices, nodelet::Nodelet)
void toPCL(const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
virtual void subtract(const PCLIndicesMsg::ConstPtr &src1, const PCLIndicesMsg::ConstPtr &src2)
boost::shared_ptr< ros::NodeHandle > pnh_
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)
c
pcl::PointIndices PCLIndicesMsg
message_filters::Subscriber< PCLIndicesMsg > sub_src1_
std::vector< int > subIndices(const std::vector< int > &a, const std::vector< int > &b)
std_msgs::Header fromPCL(const pcl::PCLHeader &pcl_header)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_


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