add_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) 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/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);
47  onInitPostProcess();
48  }
49 
51  // message_filters::Synchronizer needs to be called reset
52  // before message_filters::Subscriber is freed.
53  // Calling reset fixes the following error on shutdown of the nodelet:
54  // terminate called after throwing an instance of
55  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
56  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
57  // Also see https://github.com/ros/ros_comm/issues/720 .
58  sync_.reset();
59  async_.reset();
60  }
61 
63  {
64  sub_src1_.subscribe(*pnh_, "input/src1", 1);
65  sub_src2_.subscribe(*pnh_, "input/src2", 1);
66  if (approximate_sync_) {
67  async_ = boost::make_shared<message_filters::Synchronizer<ASyncPolicy> >(100);
68  async_->connectInput(sub_src1_, sub_src2_);
69  async_->registerCallback(
70  boost::bind(&AddPointIndices::add,
71  this, _1, _2));
72  }
73  else {
74  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
75  sync_->connectInput(sub_src1_, sub_src2_);
76  sync_->registerCallback(
77  boost::bind(&AddPointIndices::add,
78  this, _1, _2));
79  }
80  }
81 
83  {
86  }
87 
89  const PCLIndicesMsg::ConstPtr& src1,
90  const PCLIndicesMsg::ConstPtr& src2)
91  {
92  vital_checker_->poke();
93  pcl::PointIndices a, b;
96  pcl::PointIndices::Ptr c = jsk_recognition_utils::addIndices(a, b);
97  c->header = a.header;
98  PCLIndicesMsg ros_indices;
99  pcl_conversions::fromPCL(*c, ros_indices);
100  ros_indices.header = src1->header;
101  pub_.publish(ros_indices);
102  }
103 }
104 
107 
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
_2
boost::arg< 2 > _2
src2
src2
jsk_pcl_ros_utils::AddPointIndices::subscribe
virtual void subscribe()
Definition: add_point_indices_nodelet.cpp:62
PCLIndicesMsg
pcl::PointIndices PCLIndicesMsg
jsk_pcl_ros_utils::AddPointIndices::onInit
virtual void onInit()
Definition: add_point_indices_nodelet.cpp:42
pcl_conversions::toPCL
void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
jsk_pcl_ros_utils::AddPointIndices
Definition: add_point_indices.h:85
jsk_pcl_ros_utils::AddPointIndices::add
virtual void add(const PCLIndicesMsg::ConstPtr &src1, const PCLIndicesMsg::ConstPtr &src2)
Definition: add_point_indices_nodelet.cpp:88
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_pcl_ros_utils::AddPointIndices::async_
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
Definition: add_point_indices.h:142
class_list_macros.h
pcl_conversions::fromPCL
void fromPCL(const pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
add_point_indices.h
_1
boost::arg< 1 > _1
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::AddPointIndices, nodelet::Nodelet)
jsk_pcl_ros_utils::AddPointIndices::unsubscribe
virtual void unsubscribe()
Definition: add_point_indices_nodelet.cpp:82
jsk_pcl_ros_utils::AddPointIndices::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: add_point_indices.h:141
src1
src1
message_filters::Subscriber::subscribe
void subscribe()
jsk_recognition_utils::addIndices
pcl::PointIndices::Ptr addIndices(const pcl::PointIndices &a, const pcl::PointIndices &b)
nodelet::Nodelet
jsk_pcl_ros_utils::AddPointIndices::sub_src1_
message_filters::Subscriber< PCLIndicesMsg > sub_src1_
Definition: add_point_indices.h:139
jsk_pcl_ros_utils::AddPointIndices::approximate_sync_
bool approximate_sync_
Definition: add_point_indices.h:143
jsk_pcl_ros_utils::AddPointIndices::sub_src2_
message_filters::Subscriber< PCLIndicesMsg > sub_src2_
Definition: add_point_indices.h:140
jsk_pcl_ros_utils::AddPointIndices::pub_
ros::Publisher pub_
Definition: add_point_indices.h:138
jsk_pcl_ros_utils::AddPointIndices::~AddPointIndices
virtual ~AddPointIndices()
Definition: add_point_indices_nodelet.cpp:50


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43