polygon_array_likelihood_filter_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2017, 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 #include <algorithm>
38 
39 namespace jsk_pcl_ros_utils
40 {
42  {
43  DiagnosticNodelet::onInit();
44 
45  srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
46  dynamic_reconfigure::Server<Config>::CallbackType f =
47  boost::bind(&PolygonArrayLikelihoodFilter::configCallback, this, _1, _2);
48  srv_->setCallback(f);
49 
50  pub_polygons_ = advertise<jsk_recognition_msgs::PolygonArray>(
51  *pnh_, "output_polygons", 1);
52 
53  pnh_->param<bool>("use_coefficients", use_coefficients_, true);
54  if (use_coefficients_) {
55  pub_coefficients_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
56  *pnh_, "output_coefficients", 1);
57  }
58 
60  }
61 
63  {
64  if (use_coefficients_) {
65  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
66  sub_polygons_.subscribe(*pnh_, "input_polygons", 1);
67  sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
68  sync_->connectInput(sub_polygons_, sub_coefficients_);
69  sync_->registerCallback(boost::bind(
71  this, _1, _2));
72  } else {
73  sub_polygons_alone_ = pnh_->subscribe(
74  "input_polygons", 1, &PolygonArrayLikelihoodFilter::filter, this);
75  }
76  }
77 
79  {
80  if (use_coefficients_) {
83  } else {
85  }
86  }
87 
89  {
90  boost::mutex::scoped_lock lock(mutex_);
91  threshold_ = config.threshold;
92  negative_ = config.negative;
93  if (queue_size_ != config.queue_size) {
94  queue_size_ = config.queue_size;
95  unsubscribe();
96  subscribe();
97  }
98  }
99 
101  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons)
102  {
103  jsk_recognition_msgs::ModelCoefficientsArray::Ptr dummy;
104  dummy.reset();
105  filter(polygons, dummy);
106  }
107 
109  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
110  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients)
111  {
112  boost::mutex::scoped_lock lock(mutex_);
113  if (polygons->polygons.size() != polygons->likelihood.size()) {
114  ROS_ERROR_STREAM_THROTTLE(1.0, "The size of polygons " << polygons->polygons.size()
115  << " must be same as the size of likelihood "
116  << polygons->likelihood.size());
117  return;
118  }
119  if (use_coefficients_ &&
120  polygons->polygons.size() != coefficients->coefficients.size()) {
121  ROS_ERROR_STREAM_THROTTLE(1.0, "The size of polygons " << polygons->polygons.size()
122  << "must be same as the size of coeeficients "
123  << coefficients->coefficients.size());
124  return;
125  }
126  vital_checker_->poke();
127 
128  bool use_labels = polygons->polygons.size() == polygons->labels.size();
129 
130  std::vector<std::pair<double, int> > lookup_table;
131  lookup_table.resize(polygons->polygons.size());
132  for (int i = 0; i < polygons->polygons.size(); ++i) {
133  lookup_table[i] = std::pair<double, int>(polygons->likelihood[i], i);
134  }
135  std::sort(lookup_table.rbegin(), lookup_table.rend());
136 
137  jsk_recognition_msgs::PolygonArray ret_polygons;
138  jsk_recognition_msgs::ModelCoefficientsArray ret_coefficients;
139 
140  for (int i = 0; i < lookup_table.size(); ++i) {
141  double likelihood = lookup_table[i].first;
142  int idx = lookup_table[i].second;
143  if ((!negative_ && likelihood >= threshold_) ||
144  (negative_ && likelihood < threshold_)) {
145  ret_polygons.polygons.push_back(polygons->polygons[idx]);
146  ret_polygons.likelihood.push_back(polygons->likelihood[idx]);
147  if (use_labels) {
148  ret_polygons.labels.push_back(polygons->labels[idx]);
149  }
150  if (use_coefficients_) {
151  ret_coefficients.coefficients.push_back(coefficients->coefficients[idx]);
152  }
153  }
154  }
155 
156  ret_polygons.header = polygons->header;
157  pub_polygons_.publish(ret_polygons);
158  if (use_coefficients_) {
159  ret_coefficients.header = coefficients->header;
160  pub_coefficients_.publish(ret_coefficients);
161  }
162  }
163 }
164 
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
f
lock
void publish(const boost::shared_ptr< M > &message) const
virtual void filter(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonArrayLikelihoodFilter, nodelet::Nodelet)
boost::shared_ptr< ros::NodeHandle > pnh_
likelihood
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)
#define ROS_ERROR_STREAM_THROTTLE(rate, args)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_


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