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 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     filtered_box_pub_
00075       = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, "output_box", 1);
00076     filtered_indices_pub_
00077       = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output_indices", 1);
00078 
00079     
00080   }
00081 
00082   void BoundingBoxFilter::subscribe()
00083   {
00084     sub_box_.subscribe(*pnh_, "input_box", 1);
00085     sub_indices_.subscribe(*pnh_, "input_indices", 1);
00086     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00087     sync_->connectInput(sub_box_, sub_indices_);
00088     sync_->registerCallback(boost::bind(&BoundingBoxFilter::filter, this, _1, _2));
00089   }
00090 
00091   void BoundingBoxFilter::unsubscribe()
00092   {
00093     sub_box_.unsubscribe();
00094     sub_indices_.unsubscribe();
00095   }
00096 
00097   void BoundingBoxFilter::filter(
00098     const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array_msg,
00099     const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg)
00100   {
00101     boost::mutex::scoped_lock lock(mutex_);
00102 
00103     if (box_array_msg->boxes.size() != indices_msg->cluster_indices.size()) {
00104       JSK_NODELET_ERROR(
00105         "the size of message ~input_box and ~input_indices are different");
00106       return;
00107     }
00108     vital_checker_->poke();
00109 
00110     jsk_recognition_msgs::BoundingBoxArray filtered_box_array;
00111     jsk_recognition_msgs::ClusterPointIndices filtered_indices;
00112     filtered_box_array.header = box_array_msg->header;
00113     filtered_indices.header = indices_msg->header;
00114     int remove_count = 0;
00115     int pass_count = 0;
00116     for (size_t i = 0; i < box_array_msg->boxes.size(); i++) {
00117       jsk_recognition_msgs::BoundingBox box = box_array_msg->boxes[i];
00118       bool filterp = false;
00119       if (!filter_limit_negative_) {
00120         if (use_x_dimension_) {
00121           if (box.dimensions.x < x_dimension_min_ ||
00122               box.dimensions.x > x_dimension_max_) {
00123             filterp = true;
00124           }
00125         }
00126         if (use_y_dimension_) {
00127           if (box.dimensions.y < y_dimension_min_ ||
00128               box.dimensions.y > y_dimension_max_) {
00129             filterp = true;
00130           }
00131         }
00132         if (use_z_dimension_) {
00133           if (box.dimensions.z < z_dimension_min_ ||
00134               box.dimensions.z > z_dimension_max_) {
00135             filterp = true;
00136           }
00137         }
00138       }
00139       else {
00140         if (use_x_dimension_) {
00141           if (box.dimensions.x > x_dimension_min_ &&
00142               box.dimensions.x < x_dimension_max_) {
00143             filterp = true;
00144           }
00145         }
00146         if (use_y_dimension_) {
00147           if (box.dimensions.y > y_dimension_min_ &&
00148               box.dimensions.y < y_dimension_max_) {
00149             filterp = true;
00150           }
00151         }
00152         if (use_z_dimension_) {
00153           if (box.dimensions.z > z_dimension_min_ &&
00154               box.dimensions.z < z_dimension_max_) {
00155             filterp = true;
00156           }
00157         }
00158       }
00159       if (!filterp) {
00160         filtered_box_array.boxes.push_back(box);
00161         filtered_indices.cluster_indices.push_back(
00162           indices_msg->cluster_indices[i]);
00163         ++pass_count;
00164       }
00165       else {
00166         ++remove_count;
00167       }
00168     }
00169     filtered_box_pub_.publish(filtered_box_array);
00170     filtered_indices_pub_.publish(filtered_indices);
00171     remove_counter_.add(remove_count);
00172     pass_counter_.add(pass_count);
00173   }
00174 
00175   void BoundingBoxFilter::configCallback(Config &config, uint32_t level)
00176   {
00177     boost::mutex::scoped_lock lock(mutex_);
00178     filter_limit_negative_ = config.filter_limit_negative;
00179     use_x_dimension_ = config.use_x_dimension;
00180     use_y_dimension_ = config.use_y_dimension;
00181     use_z_dimension_ = config.use_z_dimension;
00182     x_dimension_min_ = config.x_dimension_min;
00183     x_dimension_max_ = config.x_dimension_max;
00184     y_dimension_min_ = config.y_dimension_min;
00185     y_dimension_max_ = config.y_dimension_max;
00186     z_dimension_min_ = config.z_dimension_min;
00187     z_dimension_max_ = config.z_dimension_max;
00188   }
00189   
00190   void BoundingBoxFilter::updateDiagnostic(
00191     diagnostic_updater::DiagnosticStatusWrapper &stat)
00192   {
00193     if (vital_checker_->isAlive()) {
00194       stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00195                    "BoundingBoxArray running");
00196       stat.add("Number of filtered box (Avg.)", remove_counter_.mean());
00197       stat.add("Number of passed box (Avg.)", pass_counter_.mean());
00198       addDiagnosticBooleanStat("Use x dimension", use_x_dimension_, stat);
00199       stat.add("minimum x dimension", x_dimension_min_);
00200       stat.add("maximum x dimension", x_dimension_max_);
00201       addDiagnosticBooleanStat("Use y dimension", use_y_dimension_, stat);
00202       stat.add("minimum y dimension", y_dimension_min_);
00203       stat.add("maximum y dimension", y_dimension_max_);
00204       addDiagnosticBooleanStat("Use z dimension", use_z_dimension_, stat);
00205       stat.add("minimum z dimension", z_dimension_min_);
00206       stat.add("maximum z dimension", z_dimension_max_);
00207       addDiagnosticBooleanStat("Filter limit negative",
00208                                filter_limit_negative_, stat);
00209     }
00210     else {
00211       addDiagnosticErrorSummary(
00212         "BoundingBoxArray", vital_checker_, stat);
00213     }
00214   }
00215   
00216 }
00217 
00218 #include <pluginlib/class_list_macros.h>
00219 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::BoundingBoxFilter, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:47