polygon_array_area_likelihood_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, 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 #define BOOST_PARAMETER_MAX_ARITY 7
00037 
00038 #include "jsk_pcl_ros/polygon_array_area_likelihood.h"
00039 #include "jsk_pcl_ros/tf_listener_singleton.h"
00040 #include "jsk_pcl_ros/geo_util.h"
00041 #include "jsk_pcl_ros/pcl_conversion_util.h"
00042 
00043 namespace jsk_pcl_ros
00044 {
00045   void PolygonArrayAreaLikelihood::onInit()
00046   {
00047     DiagnosticNodelet::onInit();
00048     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00049     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00050       boost::bind (&PolygonArrayAreaLikelihood::configCallback, this, _1, _2);
00051     srv_->setCallback (f);
00052     pub_ = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output", 1);
00053   }
00054 
00055   void PolygonArrayAreaLikelihood::subscribe()
00056   {
00057     sub_ = pnh_->subscribe(
00058       "input", 1, &PolygonArrayAreaLikelihood::likelihood, this);
00059   }
00060 
00061   void PolygonArrayAreaLikelihood::unsubscribe()
00062   {
00063     sub_.shutdown();
00064   }
00065 
00066   void PolygonArrayAreaLikelihood::likelihood(
00067     const jsk_recognition_msgs::PolygonArray::ConstPtr& msg)
00068   {
00069     boost::mutex::scoped_lock lock(mutex_);
00070     jsk_recognition_msgs::PolygonArray new_msg(*msg);
00071 
00072     double min_area = DBL_MAX;
00073     double max_area = - DBL_MAX;
00074     std::vector<double> areas; 
00075     for (size_t i = 0; i < msg->polygons.size(); i++) {
00076       Polygon::Ptr polygon = Polygon::fromROSMsgPtr(msg->polygons[i].polygon);
00077       double area = polygon->area();
00078       min_area = std::min(area, min_area);
00079       max_area = std::max(area, max_area);
00080       areas.push_back(area);
00081     }
00082 
00083     // Normalization
00084     for (size_t i = 0; i < areas.size(); i++) {
00085       double diff = areas[i] - area_;
00086       double likelihood = 1 / (1 + (diff * diff));
00087       if (msg->likelihood.size() == 0) {
00088         new_msg.likelihood.push_back(likelihood);
00089       }
00090       else {
00091         new_msg.likelihood[i] = new_msg.likelihood[i] * likelihood;
00092       }
00093     }
00094     pub_.publish(new_msg);
00095   }
00096 
00097   void PolygonArrayAreaLikelihood::configCallback(
00098     Config& config, uint32_t level)
00099   {
00100     boost::mutex::scoped_lock lock(mutex_);
00101     area_ = config.area;
00102   }
00103   
00104   
00105 }
00106 
00107 #include <pluginlib/class_list_macros.h>
00108 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::PolygonArrayAreaLikelihood,
00109                         nodelet::Nodelet);


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