cluster_point_indices_label_filter_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, 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 
38 namespace jsk_pcl_ros_utils
39 {
40 
42  {
43  DiagnosticNodelet::onInit();
44  pnh_->param("approximate_sync", approximate_sync_, false);
45  pnh_->param("queue_size", queue_size_, 100);
46 
47  // dynamic_reconfigure
48  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
49  dynamic_reconfigure::Server<Config>::CallbackType f =
50  boost::bind (&ClusterPointIndicesLabelFilter::configCallback, this, _1, _2);
51  srv_->setCallback (f);
52 
53  pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output", 1);
55  }
56 
58  {
59  boost::mutex::scoped_lock lock(mutex_);
60  label_value_ = config.label_value;
61  }
62 
64  {
65  sub_indices_.subscribe(*pnh_, "input/indices", 1);
66  sub_labels_.subscribe(*pnh_, "input/labels", 1);
67  if (approximate_sync_) {
68  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
69  async_->connectInput(sub_indices_, sub_labels_);
70  async_->registerCallback(boost::bind(&ClusterPointIndicesLabelFilter::filter,
71  this, _1, _2));
72  }
73  else {
74  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
75  sync_->connectInput(sub_indices_, sub_labels_);
76  sync_->registerCallback(boost::bind(&ClusterPointIndicesLabelFilter::filter,
77  this, _1, _2));
78  }
79  }
80 
82  {
85  }
86 
88  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& cluster_msg,
89  const jsk_recognition_msgs::LabelArray::ConstPtr& label_msg)
90  {
91  jsk_recognition_msgs::ClusterPointIndices filtered_msg;
92  filtered_msg.header = cluster_msg->header;
93  // check if sizes match?
94  for (size_t i = 0; i < label_msg->labels.size(); i++) {
95  if(label_msg->labels[i].id == label_value_)
96  filtered_msg.cluster_indices.push_back(cluster_msg->cluster_indices[i]);
97  }
98  pub_.publish(filtered_msg);
99  }
100 
101 }
102 
f
lock
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void filter(const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &cluster_msg, const jsk_recognition_msgs::LabelArray::ConstPtr &label_msg)
message_filters::Subscriber< jsk_recognition_msgs::LabelArray > sub_labels_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
boost::shared_ptr< ros::NodeHandle > pnh_
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)
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
jsk_pcl_ros_utils::ClusterPointIndicesLabelFilterConfig Config
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::ClusterPointIndicesLabelFilter, nodelet::Nodelet)


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