polygon_array_unwrapper_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 
36 #include <algorithm>
38 
39 namespace jsk_pcl_ros_utils
40 {
42  {
43  ConnectionBasedNodelet::onInit();
44  pub_polygon_ = advertise<geometry_msgs::PolygonStamped>(
45  *pnh_, "output_polygon", 1);
47  = advertise<pcl_msgs::ModelCoefficients>(
48  *pnh_,
49  "output_coefficients", 1);
50  srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
51  dynamic_reconfigure::Server<Config>::CallbackType f =
52  boost::bind(&PolygonArrayUnwrapper::configCallback, this, _1, _2);
53  srv_->setCallback(f);
54  }
55 
57  {
58  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
59  sub_polygon_.subscribe(*pnh_, "input_polygons", 1);
60  sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
61  sync_->connectInput(sub_polygon_, sub_coefficients_);
62  sync_->registerCallback(boost::bind(
64  this, _1, _2));
65  }
66 
68  {
71  }
72 
73  void PolygonArrayUnwrapper::configCallback(Config& config, uint32_t level)
74  {
75  boost::mutex::scoped_lock lock(mutex_);
76  use_likelihood_ = config.use_likelihood;
77  plane_index_ = (size_t)config.plane_index;
78  }
79 
81  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
82  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients)
83  {
84  boost::mutex::scoped_lock lock(mutex_);
85  if (polygons->polygons.size() > 0) {
86  size_t selected_index = plane_index_;
87  if (selected_index >= polygons->polygons.size()) {
88  NODELET_ERROR_THROTTLE(1.0, "plane_index exceeds polygons size");
89  selected_index = polygons->polygons.size() - 1;
90  }
91  if (use_likelihood_) {
92  // index of maximum likelihood
93  selected_index = std::distance(
94  polygons->likelihood.begin(),
95  std::max_element(polygons->likelihood.begin(), polygons->likelihood.end()));
96  }
97  geometry_msgs::PolygonStamped polygon_msg = polygons->polygons[selected_index];
98  pcl_msgs::ModelCoefficients coefficients_msg = coefficients->coefficients[selected_index];
99  pub_polygon_.publish(polygon_msg);
100  pub_coefficients_.publish(coefficients_msg);
101  }
102  }
103 }
104 
f
lock
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
#define NODELET_ERROR_THROTTLE(rate,...)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonArrayUnwrapper, nodelet::Nodelet)
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
virtual void unwrap(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients)
boost::shared_ptr< ros::NodeHandle > pnh_
virtual void configCallback(Config &config, uint32_t level)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
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_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15