multi_plane_sac_segmentation_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 
37 #include <pcl/sample_consensus/method_types.h>
38 #include <pcl/sample_consensus/model_types.h>
39 #include <pcl/segmentation/sac_segmentation.h>
40 #include <pcl/filters/extract_indices.h>
43 
44 namespace jsk_pcl_ros
45 {
47  {
48  ConnectionBasedNodelet::onInit();
49  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
50  dynamic_reconfigure::Server<Config>::CallbackType f =
51  boost::bind (&MultiPlaneSACSegmentation::configCallback, this, _1, _2);
52  srv_->setCallback (f);
53  pnh_->param("use_normal", use_normal_, false);
54  pnh_->param("use_clusters", use_clusters_, false);
55  pnh_->param("use_imu_parallel", use_imu_parallel_, false);
56  pnh_->param("use_imu_perpendicular", use_imu_perpendicular_, false);
57 
59  NODELET_ERROR("Cannot use ~use_imu_perpendicular and ~use_imu_parallel at the same time");
60  return;
61  }
64  }
66  // publishers
68  pub_inliers_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output_indices", 1);
70  = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_, "output_coefficients", 1);
71  pub_polygons_ = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output_polygons", 1);
73  }
74 
76  {
78  // subscriber
81  sub_input_.subscribe(*pnh_, "input", 1);
82  sub_imu_.subscribe(*pnh_, "input_imu", 1);
83  if (use_normal_) {
84  sub_normal_.subscribe(*pnh_, "input_normal", 1);
85  sync_normal_imu_ = boost::make_shared<NormalImuSynchronizer>(100);
87  sync_normal_imu_->registerCallback(
88  boost::bind(
90  this, _1, _2, _3));
91  }
92  else {
93  sync_imu_ = boost::make_shared<message_filters::Synchronizer<SyncImuPolicy> >(100);
94  sync_imu_->connectInput(sub_input_, sub_imu_);
95  sync_imu_->registerCallback(boost::bind(
97  this, _1, _2));
98  }
99  }
100  else if (use_normal_) {
101  sub_input_.subscribe(*pnh_, "input", 1);
102  sub_normal_.subscribe(*pnh_, "input_normal", 1);
103  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
104  sync_->connectInput(sub_input_, sub_normal_);
105  sync_->registerCallback(boost::bind(&MultiPlaneSACSegmentation::segment,
106  this, _1, _2));
107  }
108  else if (use_clusters_) {
109  NODELET_INFO("use clusters");
110  sub_input_.subscribe(*pnh_, "input", 1);
111  sub_clusters_.subscribe(*pnh_, "input_clusters", 1);
113  = boost::make_shared<message_filters::Synchronizer<SyncClusterPolicy> >(100);
114  sync_cluster_->connectInput(sub_input_, sub_clusters_);
115  sync_cluster_->registerCallback(
117  this, _1, _2));
118  }
119  else {
120  sub_ = pnh_->subscribe("input", 1, &MultiPlaneSACSegmentation::segment, this);
121  }
122  }
123 
125  {
127  // subscriber
129  if (use_normal_) {
132  }
133  else if (use_clusters_) {
136  }
137  else {
138  sub_.shutdown();
139  }
140  }
141 
142  void MultiPlaneSACSegmentation::configCallback (Config &config, uint32_t level)
143  {
144  boost::mutex::scoped_lock lock(mutex_);
145  outlier_threshold_ = config.outlier_threshold;
146  min_inliers_ = config.min_inliers;
147  min_points_ = config.min_points;
148  max_iterations_ = config.max_iterations;
149  eps_angle_ = config.eps_angle;
150  normal_distance_weight_ = config.normal_distance_weight;
151  min_trial_ = config.min_trial;
152  }
153 
155  const pcl::PointCloud<PointT>::Ptr& input,
156  const pcl::PointCloud<pcl::Normal>::Ptr& normal,
157  const Eigen::Vector3f& imu_vector,
158  std::vector<pcl::PointIndices::Ptr>& output_inliers,
159  std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients,
160  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& output_polygons)
161  {
162  pcl::PointCloud<PointT>::Ptr rest_cloud (new pcl::PointCloud<PointT>);
163  pcl::PointCloud<pcl::Normal>::Ptr rest_normal (new pcl::PointCloud<pcl::Normal>);
164  *rest_cloud = *input;
165  *rest_normal = *normal;
166  int counter = 0;
167  while (true) {
168  NODELET_INFO("apply RANSAC: %d", counter);
169  ++counter;
170  pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
171  pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
172  if (!use_normal_) {
173  pcl::SACSegmentation<PointT> seg;
174  seg.setOptimizeCoefficients (true);
175  seg.setRadiusLimits(0.3, std::numeric_limits<double>::max ());
176  seg.setMethodType (pcl::SAC_RANSAC);
177  seg.setDistanceThreshold (outlier_threshold_);
178  seg.setInputCloud(rest_cloud);
179  seg.setMaxIterations (max_iterations_);
180  if (use_imu_parallel_) {
181  seg.setModelType(pcl::SACMODEL_PARALLEL_PLANE);
182  seg.setAxis(imu_vector);
183  seg.setEpsAngle(eps_angle_);
184  }
185  else if (use_imu_perpendicular_) {
186  seg.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE);
187  seg.setAxis(imu_vector);
188  seg.setEpsAngle(eps_angle_);
189  }
190  else {
191  seg.setModelType (pcl::SACMODEL_PLANE);
192  }
193  seg.segment (*inliers, *coefficients);
194  }
195  else {
196  pcl::SACSegmentationFromNormals<PointT, pcl::Normal> seg;
197  seg.setOptimizeCoefficients (true);
198 
199  seg.setMethodType (pcl::SAC_RANSAC);
200  seg.setDistanceThreshold (outlier_threshold_);
201  seg.setNormalDistanceWeight(normal_distance_weight_);
202  seg.setInputCloud(rest_cloud);
203  seg.setInputNormals(rest_normal);
204  seg.setMaxIterations (max_iterations_);
205  if (use_imu_parallel_) {
206  seg.setModelType (pcl::SACMODEL_NORMAL_PARALLEL_PLANE);
207  seg.setAxis(imu_vector);
208  seg.setEpsAngle(eps_angle_);
209  }
210  else if (use_imu_perpendicular_) {
211  seg.setModelType (pcl::SACMODEL_NORMAL_PLANE);
212  seg.setAxis(imu_vector);
213  seg.setEpsAngle(eps_angle_);
214  }
215  else {
216  seg.setModelType (pcl::SACMODEL_NORMAL_PLANE);
217  }
218  seg.segment (*inliers, *coefficients);
219  }
220  NODELET_INFO("inliers: %lu", inliers->indices.size());
221  if (inliers->indices.size() >= min_inliers_) {
222  output_inliers.push_back(inliers);
223  output_coefficients.push_back(coefficients);
224  jsk_recognition_utils::ConvexPolygon::Ptr convex = jsk_recognition_utils::convexFromCoefficientsAndInliers<PointT>(
225  input, inliers, coefficients);
226  output_polygons.push_back(convex);
227  }
228  else {
229  if (min_trial_ <= counter) {
230  return;
231  }
232  }
233 
234  // prepare for next loop
235  pcl::PointCloud<PointT>::Ptr next_rest_cloud
236  (new pcl::PointCloud<PointT>);
237  pcl::PointCloud<pcl::Normal>::Ptr next_rest_normal
238  (new pcl::PointCloud<pcl::Normal>);
239  pcl::ExtractIndices<PointT> ex;
240  ex.setInputCloud(rest_cloud);
241  ex.setIndices(inliers);
242  ex.setNegative(true);
243  ex.setKeepOrganized(true);
244  ex.filter(*next_rest_cloud);
245  if (use_normal_) {
246  pcl::ExtractIndices<pcl::Normal> ex_normal;
247  ex_normal.setInputCloud(rest_normal);
248  ex_normal.setIndices(inliers);
249  ex_normal.setNegative(true);
250  ex_normal.setKeepOrganized(true);
251  ex_normal.filter(*next_rest_normal);
252  }
253  if (next_rest_cloud->points.size() < min_points_) {
254  NODELET_INFO("no more enough points are left");
255  return;
256  }
257  rest_cloud = next_rest_cloud;
258  rest_normal = next_rest_normal;
259  }
260  }
261 
263  const sensor_msgs::PointCloud2::ConstPtr& msg,
264  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& clusters)
265  {
266  boost::mutex::scoped_lock lock(mutex_);
267  pcl::PointCloud<PointT>::Ptr input (new pcl::PointCloud<PointT>);
268  pcl::fromROSMsg(*msg, *input);
269  std::vector<pcl::PointIndices::Ptr> cluster_indices
270  = pcl_conversions::convertToPCLPointIndices(clusters->cluster_indices);
271  pcl::ExtractIndices<PointT> ex;
272  ex.setInputCloud(input);
273  ex.setKeepOrganized(true);
274  std::vector<pcl::PointIndices::Ptr> all_inliers;
275  std::vector<pcl::ModelCoefficients::Ptr> all_coefficients;
276  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> all_convexes;
277  for (size_t i = 0; i < cluster_indices.size(); i++) {
278  pcl::PointIndices::Ptr indices = cluster_indices[i];
279  pcl::PointCloud<PointT>::Ptr cluster_cloud (new pcl::PointCloud<PointT>);
280  pcl::PointCloud<pcl::Normal>::Ptr normal (new pcl::PointCloud<pcl::Normal>);
281  ex.setIndices(indices);
282 
283  ex.filter(*cluster_cloud);
284  std::vector<pcl::PointIndices::Ptr> inliers;
285  std::vector<pcl::ModelCoefficients::Ptr> coefficients;
286  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes;
287  Eigen::Vector3f dummy_imu_vector;
288  applyRecursiveRANSAC(cluster_cloud, normal, dummy_imu_vector, inliers, coefficients, convexes);
289  appendVector(all_inliers, inliers);
290  appendVector(all_coefficients, coefficients);
291  appendVector(all_convexes, convexes);
292  }
293  publishResult(msg->header, all_inliers, all_coefficients, all_convexes);
294  }
295 
297  const std_msgs::Header& header,
298  const std::vector<pcl::PointIndices::Ptr>& inliers,
299  const std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
300  const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes)
301  {
302  jsk_recognition_msgs::ClusterPointIndices ros_indices_output;
303  jsk_recognition_msgs::ModelCoefficientsArray ros_coefficients_output;
304  jsk_recognition_msgs::PolygonArray ros_polygon_output;
305  ros_indices_output.header = header;
306  ros_coefficients_output.header = header;
307  ros_polygon_output.header = header;
308  ros_indices_output.cluster_indices
310  ros_coefficients_output.coefficients
311  = pcl_conversions::convertToROSModelCoefficients(coefficients, header);
312  pub_inliers_.publish(ros_indices_output);
313  pub_coefficients_.publish(ros_coefficients_output);
314  for (size_t i = 0; i < convexes.size(); i++) {
315  geometry_msgs::PolygonStamped polygon;
316  polygon.header = header;
317  polygon.polygon = convexes[i]->toROSMsg();
318  ros_polygon_output.polygons.push_back(polygon);
319  }
320  pub_polygons_.publish(ros_polygon_output);
321  }
322 
324  const sensor_msgs::PointCloud2::ConstPtr& msg,
325  const sensor_msgs::Imu::ConstPtr& imu_msg)
326  {
327  segmentWithImu(msg, sensor_msgs::PointCloud2::ConstPtr(), imu_msg);
328  }
329 
331  const sensor_msgs::PointCloud2::ConstPtr& msg,
332  const sensor_msgs::PointCloud2::ConstPtr& normal_msg,
333  const sensor_msgs::Imu::ConstPtr& imu_msg)
334  {
335  boost::mutex::scoped_lock lock(mutex_);
336  pcl::PointCloud<PointT>::Ptr input (new pcl::PointCloud<PointT>);
337  pcl::PointCloud<pcl::Normal>::Ptr
338  normal (new pcl::PointCloud<pcl::Normal>);
339  pcl::fromROSMsg(*msg, *input);
340  if (normal_msg) {
341  pcl::fromROSMsg(*normal_msg, *normal);
342  }
343  geometry_msgs::Vector3Stamped stamped_imu, transformed_stamped_imu;
344  stamped_imu.header = imu_msg->header;
345  stamped_imu.vector = imu_msg->linear_acceleration;
346  try {
348  msg->header.frame_id, imu_msg->header.frame_id, imu_msg->header.stamp,
349  ros::Duration(0.1));
351  msg->header.frame_id, stamped_imu, transformed_stamped_imu);
352  Eigen::Vector3d imu_vectord;
353  Eigen::Vector3f imu_vector;
354  tf::vectorMsgToEigen(transformed_stamped_imu.vector, imu_vectord);
355  jsk_recognition_utils::pointFromVectorToVector<Eigen::Vector3d, Eigen::Vector3f>(
356  imu_vectord, imu_vector);
357  imu_vector = - imu_vector;
358 
359  std::vector<pcl::PointIndices::Ptr> inliers;
360  std::vector<pcl::ModelCoefficients::Ptr> coefficients;
361  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes;
362  applyRecursiveRANSAC(input, normal, imu_vector,
363  inliers, coefficients, convexes);
364  publishResult(msg->header, inliers, coefficients, convexes);
365  }
366  catch (tf2::ConnectivityException &e) {
367  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
368  }
369  catch (tf2::InvalidArgumentException &e) {
370  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
371  }
372  catch (tf2::ExtrapolationException& e) {
373  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
374  }
375 
376  }
377 
379  const sensor_msgs::PointCloud2::ConstPtr& msg,
380  const sensor_msgs::PointCloud2::ConstPtr& msg_normal)
381  {
382  boost::mutex::scoped_lock lock(mutex_);
383  pcl::PointCloud<PointT>::Ptr input (new pcl::PointCloud<PointT>);
384  pcl::PointCloud<pcl::Normal>::Ptr normal (new pcl::PointCloud<pcl::Normal>);
385  pcl::fromROSMsg(*msg, *input);
386  if (use_normal_) {
387  pcl::fromROSMsg(*msg_normal, *normal);
388  }
389  std::vector<pcl::PointIndices::Ptr> inliers;
390  std::vector<pcl::ModelCoefficients::Ptr> coefficients;
391  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes;
392  Eigen::Vector3f dummy_imu_vector;
393  applyRecursiveRANSAC(input, normal, dummy_imu_vector,
394  inliers, coefficients, convexes);
395  publishResult(msg->header, inliers, coefficients, convexes);
396  }
397 
399  const sensor_msgs::PointCloud2::ConstPtr& msg)
400  {
401  segment(msg, sensor_msgs::PointCloud2::ConstPtr());
402  }
403 }
404 
virtual void segmentWithImu(const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::Imu::ConstPtr &imu)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
#define NODELET_ERROR(...)
virtual void publishResult(const std_msgs::Header &header, const std::vector< pcl::PointIndices::Ptr > &inliers, const std::vector< pcl::ModelCoefficients::Ptr > &coefficients, const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &msg)
void publish(const boost::shared_ptr< M > &message) const
double max(const OneDataStat &d)
wrapper function for max method for boost::function
std::vector< PCLModelCoefficientMsg > convertToROSModelCoefficients(const std::vector< pcl::ModelCoefficients::Ptr > &coefficients, const std_msgs::Header &header)
virtual void segmentWithClusters(const sensor_msgs::PointCloud2::ConstPtr &msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &clusters)
coefficients
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< message_filters::Synchronizer< SyncClusterPolicy > > sync_cluster_
virtual void configCallback(Config &config, uint32_t level)
std::vector< pcl::PointIndices::Ptr > convertToPCLPointIndices(const std::vector< PCLIndicesMsg > &cluster_indices)
boost::shared_ptr< message_filters::Synchronizer< SyncNormalImuPolicy > > sync_normal_imu_
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
void appendVector(std::vector< T > &a, const std::vector< T > &b)
message_filters::Subscriber< sensor_msgs::Imu > sub_imu_
jsk_pcl_ros::MultiPlaneSACSegmentationConfig Config
void vectorMsgToEigen(const geometry_msgs::Vector3 &m, Eigen::Vector3d &e)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_clusters_
boost::shared_ptr< ros::NodeHandle > pnh_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::MultiPlaneSACSegmentation, nodelet::Nodelet)
std::vector< PCLIndicesMsg > convertToROSPointIndices(const std::vector< pcl::PointIndices::Ptr > cluster_indices, const std_msgs::Header &header)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
#define NODELET_INFO(...)
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)
static tf::TransformListener * getInstance()
void transformVector(const std::string &target_frame, const geometry_msgs::Vector3Stamped &stamped_in, geometry_msgs::Vector3Stamped &stamped_out) const
virtual void applyRecursiveRANSAC(const pcl::PointCloud< PointT >::Ptr &input, const pcl::PointCloud< pcl::Normal >::Ptr &normal, const Eigen::Vector3f &imu_vector, std::vector< pcl::PointIndices::Ptr > &output_inliers, std::vector< pcl::ModelCoefficients::Ptr > &output_coefficients, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &output_polygons)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::shared_ptr< message_filters::Synchronizer< SyncImuPolicy > > sync_imu_


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47