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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44