cluster_point_indices_decomposer_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 
37 #include <cv_bridge/cv_bridge.h>
39 #include <pcl/filters/extract_indices.h>
40 #include <pcl/common/centroid.h>
41 #include <pcl/common/common.h>
42 #include <boost/format.hpp>
43 #include <boost/range/adaptors.hpp>
44 #include <boost/range/algorithm.hpp>
45 #include <boost/range/irange.hpp>
46 #include <pcl/registration/ia_ransac.h>
47 #include <pcl/filters/project_inliers.h>
48 #include <pcl/common/pca.h>
51 #include <Eigen/Geometry>
52 #include <geometry_msgs/PoseArray.h>
53 
57 
58 namespace jsk_pcl_ros
59 {
61  {
63  sort_by_ = "z_axis";
64  }
65 
67  {
68  DiagnosticNodelet::onInit();
69  pnh_->param("publish_tf", publish_tf_, false);
70  if (publish_tf_) {
71  br_.reset(new tf::TransformBroadcaster);
72  }
73  if (!pnh_->getParam("tf_prefix", tf_prefix_))
74  {
75  if (publish_tf_) {
76  NODELET_WARN("~tf_prefix is not specified, using %s", getName().c_str());
77  }
78  tf_prefix_ = getName();
79  }
80 
81  // fixed parameters
82  pnh_->param("approximate_sync", use_async_, false);
83  pnh_->param("queue_size", queue_size_, 100);
84  pnh_->param("publish_clouds", publish_clouds_, false);
85  if (publish_clouds_) {
86  NODELET_WARN("~output%%02d are not published before subscribed, you should subscribe ~debug_output in debuging.");
87  }
88  pnh_->param("align_boxes", align_boxes_, false);
89  if (align_boxes_) {
90  pnh_->param("align_boxes_with_plane", align_boxes_with_plane_, true);
91  } else if (pnh_->hasParam("align_boxes_with_plane")) {
92  NODELET_WARN("Rosparam ~align_boxes_with_plane is used only with ~align_boxes:=true, so ignoring it.");
93  }
96  if (!pnh_->getParam("target_frame_id", target_frame_id_)) {
97  NODELET_FATAL("~target_frame_id is not specified");
98  return;
99  }
100  NODELET_INFO("Aligning bboxes with '%s' using tf transform.", target_frame_id_.c_str());
101  } else if (pnh_->hasParam("target_frame_id")) {
102  NODELET_WARN("Rosparam ~target_frame_id is used only with ~align_boxes:=true and ~align_boxes_with_plane:=true, so ignoring it.");
103  }
104  pnh_->param("force_to_flip_z_axis", force_to_flip_z_axis_, true);
105  pnh_->param<std::string>("sort_by", sort_by_, "input_indices");
106  // dynamic_reconfigure
107  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
108  dynamic_reconfigure::Server<Config>::CallbackType f =
109  boost::bind(&ClusterPointIndicesDecomposer::configCallback, this, _1, _2);
110  srv_->setCallback(f);
111 
112  negative_indices_pub_ = advertise<pcl_msgs::PointIndices>(*pnh_, "negative_indices", 1);
113  pc_pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "debug_output", 1);
114  box_pub_ = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, "boxes", 1);
115  mask_pub_ = advertise<sensor_msgs::Image>(*pnh_, "mask", 1);
116  label_pub_ = advertise<sensor_msgs::Image>(*pnh_, "label", 1);
117  centers_pub_ = advertise<geometry_msgs::PoseArray>(*pnh_, "centroid_pose_array", 1);
118  indices_pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "cluster_indices", 1);
119 
121  }
122 
124  {
125  boost::mutex::scoped_lock(mutex_);
126  max_size_ = config.max_size;
127  min_size_ = config.min_size;
128  use_pca_ = config.use_pca;
129  fill_boxes_label_with_nearest_plane_index_ = config.fill_boxes_label_with_nearest_plane_index;
130  }
131 
133  {
134  sub_input_.subscribe(*pnh_, "input", 1);
135  sub_target_.subscribe(*pnh_, "target", 1);
137  sub_polygons_.subscribe(*pnh_, "align_planes", 1);
138  sub_coefficients_.subscribe(*pnh_, "align_planes_coefficients", 1);
139  if (use_async_) {
140  async_align_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncAlignPolicy> >(queue_size_);
142  async_align_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2, _3, _4));
143  }
144  else {
145  sync_align_ = boost::make_shared<message_filters::Synchronizer<SyncAlignPolicy> >(queue_size_);
147  sync_align_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2, _3, _4));
148  }
149  }
150  else {
151  if (use_async_) {
152  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
153  async_->connectInput(sub_input_, sub_target_);
154  async_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2));
155  }
156  else {
157  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
158  sync_->connectInput(sub_input_, sub_target_);
159  sync_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2));
160  }
161  }
162  }
163 
165  {
171  }
172  }
173 
175  const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
176  const std::vector<pcl::IndicesPtr> indices_array,
177  std::vector<size_t>* argsort)
178  {
179  std::string sort_by = sort_by_;
180  bool reverse = false;
181  if (sort_by.compare(0, 1, "-") == 0)
182  {
183  reverse = true;
184  sort_by = sort_by.substr(1, sort_by.size() - 1);
185  }
186  if (sort_by == "input_indices")
187  {
188  sortIndicesOrderByIndices(input, indices_array, argsort);
189  }
190  else if (sort_by == "z_axis")
191  {
192  sortIndicesOrderByZAxis(input, indices_array, argsort);
193  }
194  else if (sort_by == "cloud_size")
195  {
196  sortIndicesOrderByCloudSize(input, indices_array, argsort);
197  }
198  else
199  {
200  NODELET_WARN_ONCE("Unsupported ~sort_by param is specified '%s', "
201  "so using the default: 'input_indices'", sort_by_.c_str());
202  sortIndicesOrderByIndices(input, indices_array, argsort);
203  return;
204  }
205  if (reverse)
206  {
207  std::reverse((*argsort).begin(), (*argsort).end());
208  }
209  }
210 
212  const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
213  const std::vector<pcl::IndicesPtr> indices_array,
214  std::vector<size_t>* argsort)
215  {
216  (*argsort).resize(indices_array.size());
217  for (size_t i = 0; i < indices_array.size(); i++)
218  {
219  (*argsort)[i] = i;
220  }
221  }
222 
224  const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
225  const std::vector<pcl::IndicesPtr> indices_array,
226  std::vector<size_t>* argsort)
227  {
228  std::vector<double> z_values;
229  pcl::ExtractIndices<pcl::PointXYZ> ex;
230  ex.setInputCloud(input);
231  for (size_t i = 0; i < indices_array.size(); i++)
232  {
233  Eigen::Vector4f center;
234  ex.setIndices(indices_array[i]);
235  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
236  ex.filter(*cloud);
237  //
238  std::vector<int> nan_indices;
239  pcl::removeNaNFromPointCloud(*cloud, *cloud, nan_indices);
240  //
241  pcl::compute3DCentroid(*cloud, center);
242  z_values.push_back(center[2]); // only focus on z value
243  }
244 
245  // sort centroids
246  // https://stackoverflow.com/a/12399290
247  (*argsort).resize(indices_array.size());
248  std::iota(argsort->begin(), argsort->end(), 0);
249  std::sort(argsort->begin(), argsort->end(),
250  [&z_values](size_t i1, size_t i2) {return z_values[i1] < z_values[i2];});
251  }
252 
254  const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
255  const std::vector<pcl::IndicesPtr> indices_array,
256  std::vector<size_t>* argsort)
257  {
258  std::vector<double> cloud_sizes;
259  pcl::ExtractIndices<pcl::PointXYZ> ex;
260  ex.setInputCloud(input);
261  for (size_t i = 0; i < indices_array.size(); i++)
262  {
263  Eigen::Vector4f center;
264  ex.setIndices(indices_array[i]);
265  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
266  ex.filter(*cloud);
267  //
268  std::vector<int> nan_indices;
269  pcl::removeNaNFromPointCloud(*cloud, *cloud, nan_indices);
270  //
271  double cloud_size = static_cast<double>(cloud->points.size());
272  cloud_sizes.push_back(cloud_size);
273  }
274 
275  // sort clouds
276  (*argsort).resize(indices_array.size());
277  std::iota(argsort->begin(), argsort->end(), 0);
278  std::sort(argsort->begin(), argsort->end(),
279  [&cloud_sizes](size_t i1, size_t i2) {return cloud_sizes[i1] < cloud_sizes[i2];});
280  }
281 
284  {
285  if (vital_checker_->isAlive()) {
286  stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
287  "ClusterPointIndicesDecomposer running");
289  "publish_clouds", publish_clouds_, stat);
291  "publish_tf", publish_tf_, stat);
293  "use_pca", use_pca_, stat);
295  "align_boxes", align_boxes_, stat);
296  stat.add("tf_prefix", tf_prefix_);
297  stat.add("Clusters (Ave.)", cluster_counter_.mean());
298  }
299  DiagnosticNodelet::updateDiagnostic(stat);
300  }
301 
303  const Eigen::Vector4f& center,
304  const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
305  const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients)
306  {
307  double min_distance = DBL_MAX;
308  int nearest_index = -1;
309  for (size_t i = 0; i < coefficients->coefficients.size(); i++) {
310  geometry_msgs::PolygonStamped polygon_msg = planes->polygons[i];
312  for (size_t j = 0; j < polygon_msg.polygon.points.size(); j++) {
314  v[0] = polygon_msg.polygon.points[j].x;
315  v[1] = polygon_msg.polygon.points[j].y;
316  v[2] = polygon_msg.polygon.points[j].z;
317  vertices.push_back(v);
318  }
319  jsk_recognition_utils::ConvexPolygon p(vertices, coefficients->coefficients[i].values);
320  double distance = p.distanceToPoint(center);
321  if (distance < min_distance) {
322  min_distance = distance;
323  nearest_index = i;
324  }
325  }
326  return nearest_index;
327  }
328 
330  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
331  pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud_transformed,
332  const Eigen::Vector4f center,
333  const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
334  const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
335  Eigen::Matrix4f& m4,
336  Eigen::Quaternionf& q,
337  int& nearest_plane_index)
338  {
339  nearest_plane_index = findNearestPlane(center, planes, coefficients);
340  if (nearest_plane_index == -1) {
341  segmented_cloud_transformed = segmented_cloud;
342  NODELET_ERROR("no planes to align boxes are given");
343  }
344  else {
345  Eigen::Vector3f normal, z_axis;
346  if (force_to_flip_z_axis_) {
347  normal[0] = - coefficients->coefficients[nearest_plane_index].values[0];
348  normal[1] = - coefficients->coefficients[nearest_plane_index].values[1];
349  normal[2] = - coefficients->coefficients[nearest_plane_index].values[2];
350  }
351  else {
352  normal[0] = coefficients->coefficients[nearest_plane_index].values[0];
353  normal[1] = coefficients->coefficients[nearest_plane_index].values[1];
354  normal[2] = coefficients->coefficients[nearest_plane_index].values[2];
355  }
356  normal = normal.normalized();
357  Eigen::Quaternionf rot;
358  rot.setFromTwoVectors(Eigen::Vector3f::UnitZ(), normal);
359  Eigen::AngleAxisf rotation_angle_axis(rot);
360  Eigen::Vector3f rotation_axis = rotation_angle_axis.axis();
361  double theta = rotation_angle_axis.angle();
362  if (std::isnan(theta) ||
363  std::isnan(rotation_axis[0]) ||
364  std::isnan(rotation_axis[1]) ||
365  std::isnan(rotation_axis[2])) {
366  segmented_cloud_transformed = segmented_cloud;
367  NODELET_ERROR("cannot compute angle to align the point cloud: [%f, %f, %f], [%f, %f, %f]",
368  z_axis[0], z_axis[1], z_axis[2],
369  normal[0], normal[1], normal[2]);
370  }
371  else {
372  Eigen::Matrix3f m = Eigen::Matrix3f::Identity() * rot;
373  if (use_pca_) {
374  // first project points to the plane
375  pcl::PointCloud<pcl::PointXYZRGB>::Ptr projected_cloud
376  (new pcl::PointCloud<pcl::PointXYZRGB>);
377  pcl::ProjectInliers<pcl::PointXYZRGB> proj;
378  proj.setModelType (pcl::SACMODEL_PLANE);
379  pcl::ModelCoefficients::Ptr
380  plane_coefficients (new pcl::ModelCoefficients);
381  plane_coefficients->values
382  = coefficients->coefficients[nearest_plane_index].values;
383  proj.setModelCoefficients(plane_coefficients);
384  proj.setInputCloud(segmented_cloud);
385  proj.filter(*projected_cloud);
386  if (projected_cloud->points.size() >= 3) {
387  pcl::PCA<pcl::PointXYZRGB> pca;
388  pca.setInputCloud(projected_cloud);
389  Eigen::Matrix3f eigen = pca.getEigenVectors();
390  m.col(0) = eigen.col(0);
391  m.col(1) = eigen.col(1);
392  // flip axis to satisfy right-handed system
393  if (m.col(0).cross(m.col(1)).dot(m.col(2)) < 0) {
394  m.col(0) = - m.col(0);
395  }
396  if (m.col(0).dot(Eigen::Vector3f::UnitX()) < 0) {
397  // rotate around z
398  m = m * Eigen::AngleAxisf(M_PI, Eigen::Vector3f::UnitZ());
399  }
400  }
401  else {
402  NODELET_ERROR("Too small indices for PCA computation");
403  return false;
404  }
405  }
406  // m4 <- m
407  for (size_t row = 0; row < 3; row++) {
408  for (size_t column = 0; column < 3; column++) {
409  m4(row, column) = m(row, column);
410  }
411  }
412  q = m;
413  q.normalize();
414  Eigen::Matrix4f inv_m = m4.inverse();
415  pcl::transformPointCloud(*segmented_cloud, *segmented_cloud_transformed, inv_m);
416  }
417  }
418  return true;
419  }
420 
422  (const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
423  const std_msgs::Header header,
424  const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
425  const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
426  geometry_msgs::Pose& center_pose_msg,
427  jsk_recognition_msgs::BoundingBox& bounding_box)
428  {
429  bounding_box.header = header;
430  if (segmented_cloud->points.size() == 0) {
431  NODELET_WARN("segmented cloud size is zero");
432  return true;
433  }
434 
435  bool is_center_valid = false;
436  Eigen::Vector4f center;
437  pcl::PointCloud<pcl::PointXYZRGB>::Ptr
438  segmented_cloud_transformed (new pcl::PointCloud<pcl::PointXYZRGB>);
439  segmented_cloud_transformed->is_dense = segmented_cloud->is_dense;
440  // align boxes if possible
441  Eigen::Matrix4f m4 = Eigen::Matrix4f::Identity();
442  Eigen::Quaternionf q = Eigen::Quaternionf::Identity();
443  int nearest_plane_index = 0;
444  if (align_boxes_) {
446  is_center_valid = pcl::compute3DCentroid(*segmented_cloud, center) != 0;
447  bool success = transformPointCloudToAlignWithPlane(segmented_cloud, segmented_cloud_transformed,
448  center, planes, coefficients, m4, q,
449  nearest_plane_index);
450  if (!success) {
451  return false;
452  }
453  }
454  else {
455  // transform point cloud to target frame
456  tf::StampedTransform tf_transform;
457  try {
459  /*listener=*/tf_listener_,
460  /*to_frame=*/header.frame_id, // box origin
461  /*from_frame=*/target_frame_id_, // sensor origin
462  /*time=*/header.stamp,
463  /*duration=*/ros::Duration(1.0));
464  }
465  catch (tf2::TransformException &e) {
466  NODELET_ERROR("Transform error: %s", e.what());
467  return false;
468  }
469  Eigen::Affine3f transform;
470  tf::transformTFToEigen(tf_transform, transform);
471  pcl::transformPointCloud(*segmented_cloud, *segmented_cloud, transform);
472 
473  is_center_valid = pcl::compute3DCentroid(*segmented_cloud, center) != 0;
474 
475  // compute planes from target frame
476  pcl::PointXYZRGB min_pt, max_pt;
477  pcl::getMinMax3D(*segmented_cloud, min_pt, max_pt);
478  //
479  pcl_msgs::ModelCoefficients coef_by_frame;
480  coef_by_frame.values.push_back(0);
481  coef_by_frame.values.push_back(0);
482  coef_by_frame.values.push_back(1);
483  coef_by_frame.values.push_back(- min_pt.z);
484  jsk_recognition_msgs::ModelCoefficientsArray::Ptr coefficients_by_frame(
485  new jsk_recognition_msgs::ModelCoefficientsArray);
486  coefficients_by_frame->header.frame_id = target_frame_id_;
487  coefficients_by_frame->coefficients.push_back(coef_by_frame);
488  //
489  geometry_msgs::PolygonStamped plane_by_frame;
490  plane_by_frame.header.frame_id = target_frame_id_;
491  geometry_msgs::Point32 point;
492  point.z = min_pt.z;
493  point.x = min_pt.x;
494  point.y = min_pt.y;
495  plane_by_frame.polygon.points.push_back(point);
496  point.x = max_pt.x;
497  point.y = min_pt.y;
498  plane_by_frame.polygon.points.push_back(point);
499  point.x = max_pt.x;
500  point.y = max_pt.y;
501  plane_by_frame.polygon.points.push_back(point);
502  point.x = min_pt.x;
503  point.y = max_pt.y;
504  plane_by_frame.polygon.points.push_back(point);
505  jsk_recognition_msgs::PolygonArray::Ptr planes_by_frame(
506  new jsk_recognition_msgs::PolygonArray);
507  planes_by_frame->header.frame_id = target_frame_id_;
508  planes_by_frame->polygons.push_back(plane_by_frame);
509  //
510  bool success = transformPointCloudToAlignWithPlane(segmented_cloud, segmented_cloud_transformed,
511  center, planes_by_frame, coefficients_by_frame, m4, q,
512  nearest_plane_index);
513  if (!success) {
514  return false;
515  }
516  }
517  }
518  else {
519  if (use_pca_) {
520  if (segmented_cloud->points.size() >= 3) {
521  Eigen::Vector4f pca_centroid;
522  pcl::compute3DCentroid(*segmented_cloud, pca_centroid);
523  Eigen::Matrix3f covariance;
524  pcl::computeCovarianceMatrixNormalized(*segmented_cloud, pca_centroid, covariance);
525  Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eigen_solver(covariance, Eigen::ComputeEigenvectors);
526  Eigen::Matrix3f eigen_vectors_pca = eigen_solver.eigenvectors();
527  // This line is necessary for proper orientation in some cases. The numbers come out the same without it, but
528  // the signs are different and the box doesn't get correctly oriented in some cases.
529  eigen_vectors_pca.col(2) = eigen_vectors_pca.col(0).cross(eigen_vectors_pca.col(1));
530  // Rotate with respect to y-axis to make x-axis the first principal component
531  eigen_vectors_pca = eigen_vectors_pca * Eigen::AngleAxisf(M_PI / 2.0, Eigen::Vector3f::UnitY());
532  // Rotate around x
533  if (eigen_vectors_pca.col(2).dot(Eigen::Vector3f::UnitZ()) < 0) {
534  eigen_vectors_pca = eigen_vectors_pca * Eigen::AngleAxisf(M_PI, Eigen::Vector3f::UnitX());
535  }
536  // Transform the original cloud to the origin where the principal components correspond to the axes.
537  Eigen::Matrix4f projection_transform(Eigen::Matrix4f::Identity());
538  projection_transform.block<3,3>(0,0) = eigen_vectors_pca.transpose();
539  pcl::transformPointCloud(*segmented_cloud, *segmented_cloud_transformed, projection_transform);
540  m4.block<3, 3>(0, 0) = eigen_vectors_pca;
541  q = eigen_vectors_pca;
542  q.normalize();
543  is_center_valid = pcl::compute3DCentroid(*segmented_cloud_transformed, center) != 0;
544  center = m4 * center;
545  } else {
546  NODELET_ERROR("Too small indices for PCA computation");
547  segmented_cloud_transformed = segmented_cloud;
548  }
549  } else {
550  segmented_cloud_transformed = segmented_cloud;
551  is_center_valid = pcl::compute3DCentroid(*segmented_cloud_transformed, center) != 0;
552  }
553  }
554 
555  // create a bounding box
556  Eigen::Vector4f minpt, maxpt;
557  pcl::getMinMax3D<pcl::PointXYZRGB>(*segmented_cloud_transformed, minpt, maxpt);
558 
559  double xwidth = maxpt[0] - minpt[0];
560  double ywidth = maxpt[1] - minpt[1];
561  double zwidth = maxpt[2] - minpt[2];
562  if (!pcl_isfinite(xwidth) || !pcl_isfinite(ywidth) || !pcl_isfinite(zwidth))
563  {
564  // all points in cloud are nan or its size is 0
565  xwidth = ywidth = zwidth = 0;
566  }
567 
568  Eigen::Vector4f center2((maxpt[0] + minpt[0]) / 2.0, (maxpt[1] + minpt[1]) / 2.0, (maxpt[2] + minpt[2]) / 2.0, 1.0);
569  Eigen::Vector4f center_transformed = m4 * center2;
570 
571  // set centroid pose msg
572  if (is_center_valid) {
573  center_pose_msg.position.x = center[0];
574  center_pose_msg.position.y = center[1];
575  center_pose_msg.position.z = center[2];
576  center_pose_msg.orientation.x = q.x();
577  center_pose_msg.orientation.y = q.y();
578  center_pose_msg.orientation.z = q.z();
579  center_pose_msg.orientation.w = q.w();
580  }
581  else {
582  // set invalid pose for invalid center
583  center_pose_msg = geometry_msgs::Pose();
584  }
585 
586  // set bounding_box msg
587  bounding_box.pose.position.x = center_transformed[0];
588  bounding_box.pose.position.y = center_transformed[1];
589  bounding_box.pose.position.z = center_transformed[2];
590  bounding_box.pose.orientation.x = q.x();
591  bounding_box.pose.orientation.y = q.y();
592  bounding_box.pose.orientation.z = q.z();
593  bounding_box.pose.orientation.w = q.w();
594  bounding_box.dimensions.x = xwidth;
595  bounding_box.dimensions.y = ywidth;
596  bounding_box.dimensions.z = zwidth;
597  if (align_boxes_ &&
600  bounding_box.label = nearest_plane_index;
601  }
602  return true;
603  }
604 
606  (const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
607  size_t i,
608  pcl::PointCloud<pcl::PointXYZRGB>& debug_output)
609  {
611  for (size_t j = 0; j < segmented_cloud->points.size(); j++) {
612  pcl::PointXYZRGB p;
613  p.x= segmented_cloud->points[j].x;
614  p.y= segmented_cloud->points[j].y;
615  p.z= segmented_cloud->points[j].z;
616  p.rgb = *reinterpret_cast<float*>(&rgb);
617  debug_output.points.push_back(p);
618  }
619  }
620 
622  const sensor_msgs::PointCloud2ConstPtr &input,
623  const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
624  {
626  return;
627  }
628  std::vector<int> all_indices;
629 
630  boost::copy(
631  boost::irange(0, (int)(input->width * input->height)),
632  std::inserter(all_indices, all_indices.begin()));
633 
634  for (size_t i = 0; i < indices_input->cluster_indices.size(); i++) {
635  for (size_t j = 0; j < indices_input->cluster_indices[i].indices.size(); ++j) {
636  all_indices[indices_input->cluster_indices[i].indices[j]] = -1;
637  }
638  }
639  all_indices.erase(std::remove(all_indices.begin(), all_indices.end(), -1), all_indices.end());
640 
641  // publish all_indices
642  pcl_msgs::PointIndices ros_indices;
643  ros_indices.indices = std::vector<int>(all_indices.begin(), all_indices.end());
644  ros_indices.header = input->header;
645  negative_indices_pub_.publish(ros_indices);
646  }
647 
649  const sensor_msgs::PointCloud2ConstPtr &input,
650  const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input,
651  const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
652  const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients)
653  {
654  vital_checker_->poke();
655  if (publish_clouds_) {
656  allocatePublishers(indices_input->cluster_indices.size());
657  }
658  publishNegativeIndices(input, indices_input);
659  pcl::ExtractIndices<pcl::PointXYZRGB> extract;
660  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
661  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_xyz (new pcl::PointCloud<pcl::PointXYZ>);
662  pcl::fromROSMsg(*input, *cloud);
663  pcl::fromROSMsg(*input, *cloud_xyz);
664  cluster_counter_.add(indices_input->cluster_indices.size());
665 
666  std::vector<pcl::IndicesPtr> converted_indices;
667 
668  for (size_t i = 0; i < indices_input->cluster_indices.size(); i++)
669  {
670  pcl::IndicesPtr vindices;
671  // skip indices with points size
672  if (min_size_ > 0 &&
673  indices_input->cluster_indices[i].indices.size() < min_size_) {
674  vindices.reset (new std::vector<int> ());
675  converted_indices.push_back(vindices);
676  continue;
677  }
678  if (max_size_ > 0 &&
679  indices_input->cluster_indices[i].indices.size() > max_size_) {
680  vindices.reset (new std::vector<int> ());
681  converted_indices.push_back(vindices);
682  continue;
683  }
684  vindices.reset (new std::vector<int> (indices_input->cluster_indices[i].indices));
685  converted_indices.push_back(vindices);
686  }
687 
688  std::vector<size_t> argsort;
689  sortIndicesOrder(cloud_xyz, converted_indices, &argsort);
690  extract.setInputCloud(cloud);
691 
692  // point cloud from camera not laser
693  bool is_sensed_with_camera = (input->height != 1);
694 
695  cv::Mat mask = cv::Mat::zeros(input->height, input->width, CV_8UC1);
696  cv::Mat label = cv::Mat::zeros(input->height, input->width, CV_32SC1);
697  pcl::PointCloud<pcl::PointXYZRGB> debug_output;
698  jsk_recognition_msgs::BoundingBoxArray bounding_box_array;
699  jsk_recognition_msgs::ClusterPointIndices out_cluster_indices;
700  bounding_box_array.header = input->header;
701  geometry_msgs::PoseArray center_pose_array;
702  center_pose_array.header = input->header;
703  out_cluster_indices.header = input->header;
704  for (size_t i = 0; i < argsort.size(); i++)
705  {
706  pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
707  segmented_cloud->is_dense = cloud->is_dense;
708 
709  pcl_msgs::PointIndices out_indices_msg;
710  out_indices_msg.header = input->header;
711  out_indices_msg.indices = *(converted_indices[argsort[i]]);
712  out_cluster_indices.cluster_indices.push_back(out_indices_msg);
713 
714  pcl::PointIndices::Ptr segmented_indices (new pcl::PointIndices);
715  extract.setIndices(converted_indices[argsort[i]]);
716  extract.filter(*segmented_cloud);
717  if (publish_clouds_) {
718  sensor_msgs::PointCloud2::Ptr out_cloud(new sensor_msgs::PointCloud2);
719  pcl::toROSMsg(*segmented_cloud, *out_cloud);
720  out_cloud->header = input->header;
721  publishers_[i].publish(out_cloud);
722  }
723  // label
724  if (is_sensed_with_camera) {
725  // create mask & label image from cluster indices
726  for (size_t j = 0; j < converted_indices[argsort[i]]->size(); j++) {
727  int index = converted_indices[argsort[i]]->data()[j];
728  int width_index = index % input->width;
729  int height_index = index / input->width;
730  mask.at<uchar>(height_index, width_index) = 255;
731  // 0 should be skipped,
732  // because it is to label image as the black region is to mask image
733  label.at<int>(height_index, width_index) = (int)i + 1;
734  }
735  }
736  // adding the pointcloud into debug_output
737  addToDebugPointCloud(segmented_cloud, i, debug_output);
738 
739  // compute centoid and bounding box
740  geometry_msgs::Pose pose_msg;
741  jsk_recognition_msgs::BoundingBox bounding_box;
742  bounding_box.label = static_cast<int>(argsort[i]);
743 
744  if (!segmented_cloud->is_dense) {
745  std::vector<int> nan_indices;
746  pcl::removeNaNFromPointCloud(*segmented_cloud, *segmented_cloud, nan_indices);
747  }
748 
749  bool successp = computeCenterAndBoundingBox(
750  segmented_cloud, input->header, planes, coefficients, pose_msg, bounding_box);
751  if (!successp) {
752  return;
753  }
754  std::string target_frame;
756  target_frame = target_frame_id_;
757  }
758  else {
759  target_frame = input->header.frame_id;
760  }
761  center_pose_array.poses.push_back(pose_msg);
762  bounding_box.header.frame_id = target_frame;
763  bounding_box_array.boxes.push_back(bounding_box);
764  if (publish_tf_) {
765  tf::Transform transform;
766  transform.setOrigin(tf::Vector3(pose_msg.position.x, pose_msg.position.y, pose_msg.position.z));
768  br_->sendTransform(tf::StampedTransform(transform, input->header.stamp, target_frame,
769  tf_prefix_ + (boost::format("output%02u") % (i)).str()));
770  }
771  } // for each indices
772 
773  // Both bounding box and centroid are computed with transformed point cloud for the target frame.
775  bounding_box_array.header.frame_id = target_frame_id_;
776  center_pose_array.header.frame_id = target_frame_id_;
777  }
778 
779  if (is_sensed_with_camera) {
780  // publish mask
781  cv_bridge::CvImage mask_bridge(indices_input->header,
783  mask);
784  mask_pub_.publish(mask_bridge.toImageMsg());
785  // publish label
786  cv_bridge::CvImage label_bridge(indices_input->header,
788  label);
789  label_pub_.publish(label_bridge.toImageMsg());
790  }
791 
792  sensor_msgs::PointCloud2 debug_ros_output;
793  pcl::toROSMsg(debug_output, debug_ros_output);
794  debug_ros_output.header = input->header;
795  debug_ros_output.is_dense = false;
796  pc_pub_.publish(debug_ros_output);
797  centers_pub_.publish(center_pose_array);
798  box_pub_.publish(bounding_box_array);
799  indices_pub_.publish(out_cluster_indices);
800  }
801 
803  (const sensor_msgs::PointCloud2ConstPtr &input,
804  const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
805  {
806  extract(input, indices_input,
807  jsk_recognition_msgs::PolygonArrayConstPtr(),
808  jsk_recognition_msgs::ModelCoefficientsArrayConstPtr());
809  }
810 
812  {
813  if (num > publishers_.size())
814  {
815  for (size_t i = publishers_.size(); i < num; i++)
816  {
817  std::string topic_name = (boost::format("output%02u") % (i)).str();
818  NODELET_INFO("advertising %s", topic_name.c_str());
819  ros::Publisher publisher = pnh_->advertise<sensor_msgs::PointCloud2>(topic_name, 1);
820  publishers_.push_back(publisher);
821  }
822  }
823  }
824 
825 } // namespace jsk_pcl_ros
826 
828 // TODO: deprecate below export. because sorting by z_axis is achieved in parent class with sort_by_ = "z_axis"
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
static uint32_t colorRGBAToUInt32(std_msgs::ColorRGBA c)
#define NODELET_ERROR(...)
label
virtual bool computeCenterAndBoundingBox(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud, const std_msgs::Header header, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients, geometry_msgs::Pose &center_pose_msg, jsk_recognition_msgs::BoundingBox &bounding_box)
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
virtual void configCallback(Config &config, uint32_t level)
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
void summary(unsigned char lvl, const std::string s)
std::string target_frame
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
void sortIndicesOrderByZAxis(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
const std::string & getName() const
void addDiagnosticBooleanStat(const std::string &string_prefix, const bool value, diagnostic_updater::DiagnosticStatusWrapper &stat)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
T dot(T *pf1, T *pf2, int length)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncAlignPolicy > > async_align_
static tf::Quaternion createIdentityQuaternion()
virtual bool transformPointCloudToAlignWithPlane(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud, pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud_transformed, const Eigen::Vector4f center, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients, Eigen::Matrix4f &m4, Eigen::Quaternionf &q, int &nearest_plane_index)
q
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ClusterPointIndicesDecomposer, nodelet::Nodelet)
unsigned int index
void sortIndicesOrderByCloudSize(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
#define M_PI
boost::shared_ptr< ros::NodeHandle > pnh_
jsk_recognition_msgs::PolygonArray::ConstPtr polygon_msg
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
boost::shared_ptr< tf::TransformBroadcaster > br_
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
rgb
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_target_
rot
#define NODELET_WARN_ONCE(...)
virtual void add(double v)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
virtual void publishNegativeIndices(const sensor_msgs::PointCloud2ConstPtr &input, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
jsk_pcl_ros::ClusterPointIndicesDecomposerConfig Config
virtual int findNearestPlane(const Eigen::Vector4f &center, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients)
double x
void sortIndicesOrderByIndices(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
#define NODELET_INFO(...)
std_msgs::ColorRGBA colorCategory20(int i)
uint32_t getNumSubscribers() const
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)
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
p
void addToDebugPointCloud(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud, size_t i, pcl::PointCloud< pcl::PointXYZRGB > &debug_output)
GLfloat v[8][3]
int theta
virtual void sortIndicesOrder(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
void add(const std::string &key, const T &val)
static tf::TransformListener * getInstance()
virtual void extract(const sensor_msgs::PointCloud2ConstPtr &point, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients)
#define NODELET_FATAL(...)
boost::shared_ptr< message_filters::Synchronizer< SyncAlignPolicy > > sync_align_
cloud
Eigen::Vector3f Vertex
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
double distance(const urdf::Pose &transform)
const std::string TYPE_32SC1
sensor_msgs::ImagePtr toImageMsg() const
virtual double distanceToPoint(const Eigen::Vector4f p)


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