bounding_box_filter_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include "jsk_pcl_ros/bounding_box_filter.h"
00037 
00038 namespace jsk_pcl_ros
00039 {
00040   void BoundingBoxFilter::onInit()
00041   {
00042     ConnectionBasedNodelet::onInit();
00043 
00045     // dynamic reconfigure
00047     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00048     dynamic_reconfigure::Server<Config>::CallbackType f =
00049       boost::bind (
00050         &BoundingBoxFilter::configCallback, this, _1, _2);
00051     srv_->setCallback (f);
00052 
00054     // Diagnostics
00056     diagnostic_updater_.reset(
00057       new jsk_recognition_utils::TimeredDiagnosticUpdater(*pnh_, ros::Duration(1.0)));
00058     diagnostic_updater_->setHardwareID(getName());
00059     diagnostic_updater_->add(
00060       getName() + "::BoundingBoxFilter",
00061       boost::bind(
00062         &BoundingBoxFilter::updateDiagnostic,
00063         this,
00064         _1));
00065     double vital_rate;
00066     pnh_->param("vital_rate", vital_rate, 1.0);
00067     vital_checker_.reset(
00068       new jsk_topic_tools::VitalChecker(1 / vital_rate));
00069     diagnostic_updater_->start();
00070 
00072     // Publishers
00074     pnh_->param("with_indices", with_indices_, true);
00075     filtered_box_pub_
00076       = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, "output_box", 1);
00077     if (with_indices_) {
00078       filtered_indices_pub_
00079         = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output_indices", 1);
00080     }
00081 
00082     onInitPostProcess();
00083   }
00084 
00085   void BoundingBoxFilter::subscribe()
00086   {
00087     sub_box_.subscribe(*pnh_, "input_box", 1);
00088     if (with_indices_) {
00089       sub_indices_.subscribe(*pnh_, "input_indices", 1);
00090       sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00091       sync_->connectInput(sub_box_, sub_indices_);
00092       sync_->registerCallback(boost::bind(&BoundingBoxFilter::filterWithIndices, this, _1, _2));
00093     } else {
00094       sub_box_.registerCallback(boost::bind(&BoundingBoxFilter::filter, this, _1));
00095     }
00096   }
00097 
00098   void BoundingBoxFilter::unsubscribe()
00099   {
00100     sub_box_.unsubscribe();
00101     if (with_indices_) {
00102       sub_indices_.unsubscribe();
00103     }
00104   }
00105 
00106   void BoundingBoxFilter::filterBoundingBoxes(
00107     const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array_msg,
00108     std::vector<size_t>& keep)
00109   {
00110     for (size_t i = 0; i < box_array_msg->boxes.size(); i++) {
00111       jsk_recognition_msgs::BoundingBox box = box_array_msg->boxes[i];
00112       if (!filter_limit_negative_) {
00113         if (use_x_dimension_) {
00114           if (box.dimensions.x < x_dimension_min_ ||
00115               box.dimensions.x > x_dimension_max_) {
00116             continue;
00117           }
00118         }
00119         if (use_y_dimension_) {
00120           if (box.dimensions.y < y_dimension_min_ ||
00121               box.dimensions.y > y_dimension_max_) {
00122             continue;
00123           }
00124         }
00125         if (use_z_dimension_) {
00126           if (box.dimensions.z < z_dimension_min_ ||
00127               box.dimensions.z > z_dimension_max_) {
00128             continue;
00129           }
00130         }
00131       }
00132       else {
00133         if (use_x_dimension_) {
00134           if (box.dimensions.x > x_dimension_min_ &&
00135               box.dimensions.x < x_dimension_max_) {
00136             continue;
00137           }
00138         }
00139         if (use_y_dimension_) {
00140           if (box.dimensions.y > y_dimension_min_ &&
00141               box.dimensions.y < y_dimension_max_) {
00142             continue;
00143           }
00144         }
00145         if (use_z_dimension_) {
00146           if (box.dimensions.z > z_dimension_min_ &&
00147               box.dimensions.z < z_dimension_max_) {
00148             continue;
00149           }
00150         }
00151       }
00152       keep.push_back(i);
00153     }
00154   }
00155 
00156   void BoundingBoxFilter::filter(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array_msg)
00157   {
00158     boost::mutex::scoped_lock lock(mutex_);
00159 
00160     jsk_recognition_msgs::BoundingBoxArray filtered_box_array;
00161     filtered_box_array.header = box_array_msg->header;
00162 
00163     std::vector<size_t> keep;  // index of bounding box which will be kept
00164     filterBoundingBoxes(box_array_msg, keep);
00165     for (size_t j = 0; j < keep.size(); j++)
00166     {
00167       size_t i = keep[j];
00168       filtered_box_array.boxes.push_back(box_array_msg->boxes[i]);
00169     }
00170 
00171     // publish
00172     filtered_box_pub_.publish(filtered_box_array);
00173 
00174     // for diagnostic
00175     size_t pass_count = keep.size();
00176     size_t remove_count = box_array_msg->boxes.size() - pass_count;
00177     remove_counter_.add(remove_count);
00178     pass_counter_.add(pass_count);
00179   }
00180 
00181   void BoundingBoxFilter::filterWithIndices(
00182     const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array_msg,
00183     const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg)
00184   {
00185     boost::mutex::scoped_lock lock(mutex_);
00186 
00187     if (box_array_msg->boxes.size() != indices_msg->cluster_indices.size()) {
00188       NODELET_ERROR(
00189         "the size of message ~input_box and ~input_indices are different");
00190       return;
00191     }
00192     vital_checker_->poke();
00193 
00194     jsk_recognition_msgs::BoundingBoxArray filtered_box_array;
00195     jsk_recognition_msgs::ClusterPointIndices filtered_indices;
00196     filtered_box_array.header = box_array_msg->header;
00197     filtered_indices.header = indices_msg->header;
00198 
00199     std::vector<size_t> keep;  // index of bounding box which will be kept
00200     filterBoundingBoxes(box_array_msg, keep);
00201     for (size_t j = 0; j < keep.size(); j++)
00202     {
00203       size_t i = keep[j];
00204       filtered_box_array.boxes.push_back(box_array_msg->boxes[i]);
00205       filtered_indices.cluster_indices.push_back(indices_msg->cluster_indices[i]);
00206     }
00207 
00208     // publish
00209     filtered_box_pub_.publish(filtered_box_array);
00210     filtered_indices_pub_.publish(filtered_indices);
00211 
00212     // for diagnostic
00213     size_t pass_count = keep.size();
00214     size_t remove_count = box_array_msg->boxes.size() - pass_count;
00215     remove_counter_.add(remove_count);
00216     pass_counter_.add(pass_count);
00217   }
00218 
00219   void BoundingBoxFilter::configCallback(Config &config, uint32_t level)
00220   {
00221     boost::mutex::scoped_lock lock(mutex_);
00222     filter_limit_negative_ = config.filter_limit_negative;
00223     use_x_dimension_ = config.use_x_dimension;
00224     use_y_dimension_ = config.use_y_dimension;
00225     use_z_dimension_ = config.use_z_dimension;
00226     x_dimension_min_ = config.x_dimension_min;
00227     x_dimension_max_ = config.x_dimension_max;
00228     y_dimension_min_ = config.y_dimension_min;
00229     y_dimension_max_ = config.y_dimension_max;
00230     z_dimension_min_ = config.z_dimension_min;
00231     z_dimension_max_ = config.z_dimension_max;
00232   }
00233   
00234   void BoundingBoxFilter::updateDiagnostic(
00235     diagnostic_updater::DiagnosticStatusWrapper &stat)
00236   {
00237     if (vital_checker_->isAlive()) {
00238       stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00239                    "BoundingBoxArray running");
00240       stat.add("Number of filtered box (Avg.)", remove_counter_.mean());
00241       stat.add("Number of passed box (Avg.)", pass_counter_.mean());
00242       jsk_recognition_utils::addDiagnosticBooleanStat("Use x dimension", use_x_dimension_, stat);
00243       stat.add("minimum x dimension", x_dimension_min_);
00244       stat.add("maximum x dimension", x_dimension_max_);
00245       jsk_recognition_utils::addDiagnosticBooleanStat("Use y dimension", use_y_dimension_, stat);
00246       stat.add("minimum y dimension", y_dimension_min_);
00247       stat.add("maximum y dimension", y_dimension_max_);
00248       jsk_recognition_utils::addDiagnosticBooleanStat("Use z dimension", use_z_dimension_, stat);
00249       stat.add("minimum z dimension", z_dimension_min_);
00250       stat.add("maximum z dimension", z_dimension_max_);
00251       jsk_recognition_utils::addDiagnosticBooleanStat("Filter limit negative",
00252                                filter_limit_negative_, stat);
00253     }
00254     else {
00255       jsk_recognition_utils::addDiagnosticErrorSummary(
00256         "BoundingBoxArray", vital_checker_, stat);
00257     }
00258   }
00259   
00260 }
00261 
00262 #include <pluginlib/class_list_macros.h>
00263 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::BoundingBoxFilter, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:49