plane_rejector_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2013, Ryohei Ueda and 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 
38 
39 #include <geometry_msgs/Vector3Stamped.h>
41 
42 namespace jsk_pcl_ros_utils
43 {
45  {
46  ConnectionBasedNodelet::onInit();
49  double vital_rate;
50  pnh_->param("vital_rate", vital_rate, 1.0);
51  vital_checker_.reset(
52  new jsk_topic_tools::VitalChecker(1 / vital_rate));
53 
55  diagnostic_updater_->setHardwareID(getName());
57  getName() + "::PlaneRejector",
58  boost::bind(
60  this, _1));
61  if (!pnh_->getParam("processing_frame_id", processing_frame_id_)) {
62  NODELET_FATAL("You need to specify ~processing_frame_id");
63  return;
64  }
65  pnh_->param("use_inliers", use_inliers_, false);
66  pnh_->param("allow_flip", allow_flip_, false);
67 
68  std::vector<double> reference_axis;
70  *pnh_, "reference_axis", reference_axis)) {
71  NODELET_FATAL("you need to specify ~reference_axis");
72  return;
73  }
74  else if (reference_axis.size() != 3){
75  NODELET_FATAL("~reference_axis is not 3 length vector");
76  return;
77  }
78  else {
80  reference_axis_.normalize();
81  }
82 
83  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
84  dynamic_reconfigure::Server<Config>::CallbackType f =
85  boost::bind (&PlaneRejector::configCallback, this, _1, _2);
86  srv_->setCallback (f);
87 
88  polygons_pub_ = advertise<jsk_recognition_msgs::PolygonArray>(
89  *pnh_, "output_polygons", 1);
90  coefficients_pub_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
91  *pnh_, "output_coefficients", 1);
92  if (use_inliers_) {
93  inliers_pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output_inliers", 1);
94  }
95  else {
96  }
97  diagnostics_timer_ = pnh_->createTimer(
98  ros::Duration(1.0),
100  this,
101  _1));
103  }
104 
106  {
107  if (use_inliers_) {
108  sync_inlier_ = boost::make_shared<message_filters::Synchronizer<SyncInlierPolicy> >(100);
109  sub_polygons_.subscribe(*pnh_, "input_polygons", 1);
110  sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
111  sub_inliers_.subscribe(*pnh_, "input_inliers", 1);
113  sync_inlier_->registerCallback(boost::bind(&PlaneRejector::reject, this, _1, _2, _3));
114  }
115  else {
116  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
117  sub_polygons_.subscribe(*pnh_, "input_polygons", 1);
118  sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
119  sync_->connectInput(sub_polygons_, sub_coefficients_);
120  sync_->registerCallback(boost::bind(&PlaneRejector::reject, this, _1, _2));
121  }
122  }
123 
125  {
128  }
129 
132  {
133  bool alivep = vital_checker_->isAlive();
134  // check tf successeed or not
135  if (alivep) {
136  if (tf_success_->getValue()) {
137  stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
138  "PlaneRejector running");
139  }
140  else {
141  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
142  "failed to tf transform");
143  }
144  stat.add("Input planes (Avg.)", input_plane_counter_.mean());
145  stat.add("Rejected Planes (Avg.)", rejected_plane_counter_.mean());
146  stat.add("Passed Planes (Avg.)", passed_plane_counter_.mean());
147  stat.add("Angular Threahold", angle_thr_);
148  stat.add("Reference Axis",
149  (boost::format("[%f, %f, %f]")
150  % (reference_axis_[0])
151  % (reference_axis_[1])
152  % (reference_axis_[2])).str());
153  stat.add("Processing Frame ID", processing_frame_id_);
154  }
155  else {
156  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
157  "PlaneRejector not running");
158  }
159 
160  }
161 
163  {
164  boost::mutex::scoped_lock lock(mutex_);
165  diagnostic_updater_->update();
166  }
167 
168  void PlaneRejector::configCallback (Config &config, uint32_t level)
169  {
170  boost::mutex::scoped_lock lock(mutex_);
171  angle_thr_ = config.angle_thr;
172  angle_ = config.angle;
173  }
174 
176  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
177  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients)
178  {
179  reject(polygons, coefficients, jsk_recognition_msgs::ClusterPointIndices::ConstPtr());
180  }
181 
183  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
184  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
185  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& inliers)
186  {
187  boost::mutex::scoped_lock lock(mutex_);
188  vital_checker_->poke();
189  jsk_recognition_msgs::PolygonArray result_polygons;
190  jsk_recognition_msgs::ModelCoefficientsArray result_coefficients;
191  jsk_recognition_msgs::ClusterPointIndices result_inliers;
192  result_polygons.header = polygons->header;
193  result_coefficients.header = coefficients->header;
194  result_inliers.header = polygons->header;
195  input_plane_counter_.add(polygons->polygons.size());
196  int rejected_plane_counter = 0;
197  int passed_plane_counter = 0;
198  for (size_t i = 0; i < polygons->polygons.size(); i++) {
199  geometry_msgs::PolygonStamped polygon = polygons->polygons[i];
200  PCLModelCoefficientMsg coefficient = coefficients->coefficients[i];
201  // transform the coefficients to processing_frame_id_
202  if (listener_->canTransform(coefficient.header.frame_id,
204  coefficient.header.stamp)) {
205  tf_success_->addValue(true);
206  geometry_msgs::Vector3Stamped plane_axis;
207  plane_axis.header = coefficient.header;
208  plane_axis.vector.x = coefficient.values[0];
209  plane_axis.vector.y = coefficient.values[1];
210  plane_axis.vector.z = coefficient.values[2];
211  geometry_msgs::Vector3Stamped transformed_plane_axis;
213  plane_axis,
214  transformed_plane_axis);
215  Eigen::Vector3d eigen_transformed_plane_axis;
216  tf::vectorMsgToEigen(transformed_plane_axis.vector,
217  eigen_transformed_plane_axis);
218  if (allow_flip_ && eigen_transformed_plane_axis.normalized().dot(reference_axis_) < 0) {
219  // flip normal vector to make its direction same as reference axis
220  eigen_transformed_plane_axis = -eigen_transformed_plane_axis;
221  }
222  double ang = std::abs(acos(eigen_transformed_plane_axis.normalized().dot(reference_axis_)) - angle_);
223  if (ang < angle_thr_) {
224  ++passed_plane_counter;
225  result_polygons.polygons.push_back(polygons->polygons[i]);
226  result_coefficients.coefficients.push_back(coefficient);
227  if (use_inliers_) {
228  result_inliers.cluster_indices.push_back(inliers->cluster_indices[i]);
229  }
230  }
231  else {
232  ++rejected_plane_counter;
233  }
234  }
235  else {
236  tf_success_->addValue(false);
237  }
238  }
239  rejected_plane_counter_.add(rejected_plane_counter);
240  passed_plane_counter_.add(passed_plane_counter);
241  polygons_pub_.publish(result_polygons);
242  coefficients_pub_.publish(result_coefficients);
243  if (use_inliers_) {
244  inliers_pub_.publish(result_inliers);
245  }
246  diagnostic_updater_->update();
247  }
248 
249 }
250 
virtual void updateDiagnosticsPlaneRejector(diagnostic_updater::DiagnosticStatusWrapper &stat)
f
lock
jsk_pcl_ros_utils::PlaneRejectorConfig Config
jsk_topic_tools::VitalChecker::Ptr vital_checker_
void publish(const boost::shared_ptr< M > &message) const
void summary(unsigned char lvl, const std::string s)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
const std::string & getName() const
virtual void updateDiagnostics(const ros::TimerEvent &event)
jsk_recognition_utils::Counter passed_plane_counter_
jsk_recognition_utils::SeriesedBoolean::Ptr tf_success_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_inliers_
virtual void configCallback(Config &config, uint32_t level)
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
jsk_recognition_utils::Counter rejected_plane_counter_
bool readVectorParameter(ros::NodeHandle &nh, const std::string &param_name, std::vector< double > &result)
void vectorMsgToEigen(const geometry_msgs::Vector3 &m, Eigen::Vector3d &e)
boost::shared_ptr< message_filters::Synchronizer< SyncInlierPolicy > > sync_inlier_
boost::shared_ptr< diagnostic_updater::Updater > diagnostic_updater_
virtual void reject(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients)
boost::shared_ptr< ros::NodeHandle > pnh_
string str
jsk_recognition_utils::Counter input_plane_counter_
virtual void add(double v)
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
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)
void pointFromVectorToVector(const FromT &from, ToT &to)
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
void add(const std::string &key, const T &val)
static tf::TransformListener * getInstance()
#define NODELET_FATAL(...)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PlaneRejector, nodelet::Nodelet)
void transformVector(const std::string &target_frame, const geometry_msgs::Vector3Stamped &stamped_in, geometry_msgs::Vector3Stamped &stamped_out) const
pcl::ModelCoefficients PCLModelCoefficientMsg
tf::TransformListener * listener_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_


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