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/or 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  onInitPostProcess();
55  }
56 
58  // message_filters::Synchronizer needs to be called reset
59  // before message_filters::Subscriber is freed.
60  // Calling reset fixes the following error on shutdown of the nodelet:
61  // terminate called after throwing an instance of
62  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
63  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
64  // Also see https://github.com/ros/ros_comm/issues/720 .
65  sync_.reset();
66  }
67 
69  {
70  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
71  sub_polygon_.subscribe(*pnh_, "input_polygons", 1);
72  sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
74  sync_->registerCallback(boost::bind(
76  this, _1, _2));
77  }
78 
80  {
83  }
84 
85  void PolygonArrayUnwrapper::configCallback(Config& config, uint32_t level)
86  {
87  boost::mutex::scoped_lock lock(mutex_);
88  use_likelihood_ = config.use_likelihood;
89  plane_index_ = (size_t)config.plane_index;
90  }
91 
93  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
94  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients)
95  {
96  boost::mutex::scoped_lock lock(mutex_);
97  if (polygons->polygons.size() > 0) {
98  size_t selected_index = plane_index_;
99  if (selected_index >= polygons->polygons.size()) {
100  NODELET_ERROR_THROTTLE(1.0, "plane_index exceeds polygons size");
101  selected_index = polygons->polygons.size() - 1;
102  }
103  if (use_likelihood_) {
104  // index of maximum likelihood
105  selected_index = std::distance(
106  polygons->likelihood.begin(),
107  std::max_element(polygons->likelihood.begin(), polygons->likelihood.end()));
108  }
109  geometry_msgs::PolygonStamped polygon_msg = polygons->polygons[selected_index];
110  pcl_msgs::ModelCoefficients coefficients_msg = coefficients->coefficients[selected_index];
111  pub_polygon_.publish(polygon_msg);
112  pub_coefficients_.publish(coefficients_msg);
113  }
114  }
115 }
116 
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
polygons
polygons
jsk_pcl_ros_utils::PolygonArrayUnwrapper::sub_polygon_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
Definition: polygon_array_unwrapper.h:139
jsk_pcl_ros_utils::PolygonArrayUnwrapper::pub_polygon_
ros::Publisher pub_polygon_
Definition: polygon_array_unwrapper.h:141
NODELET_ERROR_THROTTLE
#define NODELET_ERROR_THROTTLE(rate,...)
polygon_array_unwrapper.h
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonArrayUnwrapper, nodelet::Nodelet)
lock
lock
jsk_pcl_ros_utils::PolygonArrayUnwrapper::plane_index_
size_t plane_index_
Definition: polygon_array_unwrapper.h:144
jsk_pcl_ros_utils::PolygonArrayUnwrapper::~PolygonArrayUnwrapper
virtual ~PolygonArrayUnwrapper()
Definition: polygon_array_unwrapper_nodelet.cpp:89
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_pcl_ros_utils::PolygonArrayUnwrapper::pub_coefficients_
ros::Publisher pub_coefficients_
Definition: polygon_array_unwrapper.h:142
class_list_macros.h
jsk_pcl_ros_utils::PolygonArrayUnwrapper::sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
Definition: polygon_array_unwrapper.h:140
jsk_pcl_ros_utils::PolygonArrayUnwrapper::unwrap
virtual void unwrap(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients)
Definition: polygon_array_unwrapper_nodelet.cpp:124
jsk_pcl_ros_utils::PolygonArrayUnwrapper::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: polygon_array_unwrapper.h:137
message_filters::Subscriber::subscribe
void subscribe()
f
f
nodelet::Nodelet
jsk_pcl_ros_utils::PolygonArrayUnwrapper::subscribe
virtual void subscribe()
Definition: polygon_array_unwrapper_nodelet.cpp:100
jsk_pcl_ros_utils::PolygonArrayUnwrapper::mutex_
boost::mutex mutex_
Definition: polygon_array_unwrapper.h:136
coefficients
coefficients
jsk_pcl_ros_utils::PolygonArrayUnwrapper::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: polygon_array_unwrapper_nodelet.cpp:117
jsk_pcl_ros_utils::PolygonArrayUnwrapper::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: polygon_array_unwrapper.h:138
jsk_pcl_ros_utils::PolygonArrayUnwrapper::use_likelihood_
bool use_likelihood_
Definition: polygon_array_unwrapper.h:143
jsk_pcl_ros_utils::PolygonArrayUnwrapper
Definition: polygon_array_unwrapper.h:86
jsk_pcl_ros_utils::PolygonArrayUnwrapper::unsubscribe
virtual void unsubscribe()
Definition: polygon_array_unwrapper_nodelet.cpp:111
jsk_pcl_ros_utils::PolygonArrayUnwrapper::onInit
virtual void onInit()
Definition: polygon_array_unwrapper_nodelet.cpp:73
config
config


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43