bounding_box_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
39 {
41  {
42  ConnectionBasedNodelet::onInit();
43 
45  // dynamic reconfigure
47  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
48  dynamic_reconfigure::Server<Config>::CallbackType f =
49  boost::bind (
50  &BoundingBoxFilter::configCallback, this, _1, _2);
51  srv_->setCallback (f);
52 
54  // Publishers
56  pnh_->param("with_indices", with_indices_, true);
58  = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, "output_box", 1);
59  if (with_indices_) {
61  = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output_indices", 1);
62  }
63 
65  }
66 
68  {
69  sub_box_.subscribe(*pnh_, "input_box", 1);
70  if (with_indices_) {
71  sub_indices_.subscribe(*pnh_, "input_indices", 1);
72  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
73  sync_->connectInput(sub_box_, sub_indices_);
74  sync_->registerCallback(boost::bind(&BoundingBoxFilter::filterWithIndices, this, _1, _2));
75  } else {
76  sub_box_.registerCallback(boost::bind(&BoundingBoxFilter::filter, this, _1));
77  }
78  }
79 
81  {
83  if (with_indices_) {
85  }
86  }
87 
89  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array_msg,
90  std::vector<size_t>& keep)
91  {
92  for (size_t i = 0; i < box_array_msg->boxes.size(); i++) {
93  jsk_recognition_msgs::BoundingBox box = box_array_msg->boxes[i];
95  if (use_x_dimension_) {
96  if (box.dimensions.x < x_dimension_min_ ||
97  box.dimensions.x > x_dimension_max_) {
98  continue;
99  }
100  }
101  if (use_y_dimension_) {
102  if (box.dimensions.y < y_dimension_min_ ||
103  box.dimensions.y > y_dimension_max_) {
104  continue;
105  }
106  }
107  if (use_z_dimension_) {
108  if (box.dimensions.z < z_dimension_min_ ||
109  box.dimensions.z > z_dimension_max_) {
110  continue;
111  }
112  }
113  }
114  else {
115  if (use_x_dimension_) {
116  if (box.dimensions.x > x_dimension_min_ &&
117  box.dimensions.x < x_dimension_max_) {
118  continue;
119  }
120  }
121  if (use_y_dimension_) {
122  if (box.dimensions.y > y_dimension_min_ &&
123  box.dimensions.y < y_dimension_max_) {
124  continue;
125  }
126  }
127  if (use_z_dimension_) {
128  if (box.dimensions.z > z_dimension_min_ &&
129  box.dimensions.z < z_dimension_max_) {
130  continue;
131  }
132  }
133  }
134  keep.push_back(i);
135  }
136  }
137 
138  void BoundingBoxFilter::filter(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array_msg)
139  {
140  boost::mutex::scoped_lock lock(mutex_);
141 
142  jsk_recognition_msgs::BoundingBoxArray filtered_box_array;
143  filtered_box_array.header = box_array_msg->header;
144 
145  std::vector<size_t> keep; // index of bounding box which will be kept
146  filterBoundingBoxes(box_array_msg, keep);
147  for (size_t j = 0; j < keep.size(); j++)
148  {
149  size_t i = keep[j];
150  filtered_box_array.boxes.push_back(box_array_msg->boxes[i]);
151  }
152 
153  // publish
154  filtered_box_pub_.publish(filtered_box_array);
155 
156  // for diagnostic
157  size_t pass_count = keep.size();
158  size_t remove_count = box_array_msg->boxes.size() - pass_count;
159  remove_counter_.add(remove_count);
160  pass_counter_.add(pass_count);
161  }
162 
164  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array_msg,
165  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg)
166  {
167  boost::mutex::scoped_lock lock(mutex_);
168 
169  if (box_array_msg->boxes.size() != indices_msg->cluster_indices.size()) {
171  "the size of message ~input_box and ~input_indices are different");
172  return;
173  }
174  vital_checker_->poke();
175 
176  jsk_recognition_msgs::BoundingBoxArray filtered_box_array;
177  jsk_recognition_msgs::ClusterPointIndices filtered_indices;
178  filtered_box_array.header = box_array_msg->header;
179  filtered_indices.header = indices_msg->header;
180 
181  std::vector<size_t> keep; // index of bounding box which will be kept
182  filterBoundingBoxes(box_array_msg, keep);
183  for (size_t j = 0; j < keep.size(); j++)
184  {
185  size_t i = keep[j];
186  filtered_box_array.boxes.push_back(box_array_msg->boxes[i]);
187  filtered_indices.cluster_indices.push_back(indices_msg->cluster_indices[i]);
188  }
189 
190  // publish
191  filtered_box_pub_.publish(filtered_box_array);
192  filtered_indices_pub_.publish(filtered_indices);
193 
194  // for diagnostic
195  size_t pass_count = keep.size();
196  size_t remove_count = box_array_msg->boxes.size() - pass_count;
197  remove_counter_.add(remove_count);
198  pass_counter_.add(pass_count);
199  }
200 
201  void BoundingBoxFilter::configCallback(Config &config, uint32_t level)
202  {
203  boost::mutex::scoped_lock lock(mutex_);
204  filter_limit_negative_ = config.filter_limit_negative;
205  use_x_dimension_ = config.use_x_dimension;
206  use_y_dimension_ = config.use_y_dimension;
207  use_z_dimension_ = config.use_z_dimension;
208  x_dimension_min_ = config.x_dimension_min;
209  x_dimension_max_ = config.x_dimension_max;
210  y_dimension_min_ = config.y_dimension_min;
211  y_dimension_max_ = config.y_dimension_max;
212  z_dimension_min_ = config.z_dimension_min;
213  z_dimension_max_ = config.z_dimension_max;
214  }
215 
218  {
219  if (vital_checker_->isAlive()) {
220  stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
221  "BoundingBoxArray running");
222  stat.add("Number of filtered box (Avg.)", remove_counter_.mean());
223  stat.add("Number of passed box (Avg.)", pass_counter_.mean());
225  stat.add("minimum x dimension", x_dimension_min_);
226  stat.add("maximum x dimension", x_dimension_max_);
228  stat.add("minimum y dimension", y_dimension_min_);
229  stat.add("maximum y dimension", y_dimension_max_);
231  stat.add("minimum z dimension", z_dimension_min_);
232  stat.add("maximum z dimension", z_dimension_max_);
233  jsk_topic_tools::addDiagnosticBooleanStat("Filter limit negative",
234  filter_limit_negative_, stat);
235  }
236  DiagnosticNodelet::updateDiagnostic(stat);
237  }
238 
239 }
240 
virtual void filterWithIndices(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box_array_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
void summary(unsigned char lvl, const std::string s)
void addDiagnosticBooleanStat(const std::string &string_prefix, const bool value, diagnostic_updater::DiagnosticStatusWrapper &stat)
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArray > sub_box_
void filterBoundingBoxes(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box_array_msg, std::vector< size_t > &keep)
virtual void configCallback(Config &config, uint32_t level)
jsk_pcl_ros::BoundingBoxFilterConfig Config
boost::shared_ptr< ros::NodeHandle > pnh_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::BoundingBoxFilter, nodelet::Nodelet)
virtual void add(double v)
virtual void filter(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box_array_msg)
jsk_recognition_utils::Counter remove_counter_
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
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)
jsk_recognition_utils::Counter pass_counter_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
void add(const std::string &key, const T &val)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Connection registerCallback(const C &callback)


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