polygon_array_area_likelihood_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, 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 #define BOOST_PARAMETER_MAX_ARITY 7
37 
42 
43 namespace jsk_pcl_ros_utils
44 {
46  {
47  DiagnosticNodelet::onInit();
48  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
49  typename dynamic_reconfigure::Server<Config>::CallbackType f =
50  boost::bind (&PolygonArrayAreaLikelihood::configCallback, this, _1, _2);
51  srv_->setCallback (f);
52  pub_ = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output", 1);
54  }
55 
57  {
58  sub_ = pnh_->subscribe(
59  "input", 1, &PolygonArrayAreaLikelihood::likelihood, this);
60  }
61 
63  {
64  sub_.shutdown();
65  }
66 
68  const jsk_recognition_msgs::PolygonArray::ConstPtr& msg)
69  {
70  boost::mutex::scoped_lock lock(mutex_);
71  vital_checker_->poke();
72  jsk_recognition_msgs::PolygonArray new_msg(*msg);
73 
74  double min_area = DBL_MAX;
75  double max_area = - DBL_MAX;
76  std::vector<double> areas;
77  for (size_t i = 0; i < msg->polygons.size(); i++) {
79  = jsk_recognition_utils::Polygon::fromROSMsgPtr(msg->polygons[i].polygon);
80  double area = polygon->area();
81  min_area = std::min(area, min_area);
82  max_area = std::max(area, max_area);
83  areas.push_back(area);
84  }
85 
86  // Normalization
87  for (size_t i = 0; i < areas.size(); i++) {
88  double diff = areas[i] - area_;
89  double likelihood = 1 / (1 + (diff * diff));
90  if (msg->likelihood.size() == 0) {
91  new_msg.likelihood.push_back(likelihood);
92  }
93  else {
94  new_msg.likelihood[i] = new_msg.likelihood[i] * likelihood;
95  }
96  }
97  pub_.publish(new_msg);
98  }
99 
101  Config& config, uint32_t level)
102  {
103  boost::mutex::scoped_lock lock(mutex_);
104  area_ = config.area;
105  }
106 
107 
108 }
109 
f
lock
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
static Polygon::Ptr fromROSMsgPtr(const geometry_msgs::Polygon &polygon)
boost::shared_ptr< ros::NodeHandle > pnh_
jsk_topic_tools::VitalChecker::Ptr vital_checker_
virtual void likelihood(const jsk_recognition_msgs::PolygonArray::ConstPtr &msg)
virtual void configCallback(Config &config, uint32_t level)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonArrayAreaLikelihood, nodelet::Nodelet)


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