edgebased_cube_finder_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
37 #include <pcl/kdtree/kdtree_flann.h>
38 #include <pcl/common/centroid.h>
40 #include <jsk_recognition_msgs/BoundingBoxArray.h>
41 #include <geometry_msgs/PoseArray.h>
42 #include <pcl/filters/extract_indices.h>
43 #include <visualization_msgs/Marker.h>
45 #include <pcl/sample_consensus/method_types.h>
46 #include <pcl/sample_consensus/model_types.h>
47 #include <pcl/segmentation/sac_segmentation.h>
48 #include <pcl/common/angles.h>
49 #include <jsk_recognition_msgs/PolygonArray.h>
50 #include <jsk_recognition_msgs/ClusterPointIndices.h>
51 #include <pcl/filters/project_inliers.h>
52 #include <pcl/surface/convex_hull.h>
54 
55 namespace jsk_pcl_ros
56 {
58  const CoefficientsPair& coefficients_pair,
59  const double outlier_threshold):
60  value_(0.0), indices_pair_(pair), coefficients_pair_(coefficients_pair),
61  outlier_threshold_(outlier_threshold_)
62  {
63 
64  }
65 
67  {
68  }
69 
71  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr& cloud,
72  const pcl::PointIndices::Ptr& indices,
73  Eigen::Vector3f& output)
74  {
75  Eigen::Vector4f centroid;
76  //pcl::compute3DCentroid(cloud, indices.indices, centroid);
77  pcl::PointCloud<pcl::PointXYZRGB>::Ptr target_cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
78  pcl::ExtractIndices<pcl::PointXYZRGB> ex;
79  ex.setInputCloud(cloud);
80  ex.setIndices(indices);
81  ex.filter(*target_cloud);
82  pcl::compute3DCentroid(*target_cloud, centroid);
83  jsk_recognition_utils::pointFromVectorToVector<Eigen::Vector4f, Eigen::Vector3f>(centroid, output);
84  }
85 
88  const pcl::PointCloud<pcl::PointXYZRGB>& cloud,
89  const pcl::PointIndices::Ptr indices,
91  {
92  pcl::PointCloud<pcl::PointXYZRGB>::Ptr points
93  (new pcl::PointCloud<pcl::PointXYZRGB>);
94  pcl::ExtractIndices<pcl::PointXYZRGB> extract;
95  extract.setInputCloud(cloud.makeShared());
96  extract.setIndices(indices);
97  extract.filter(*points);
98  for (size_t i = 0; i < points->points.size(); i++) {
99  pcl::PointXYZRGB p = points->points[i];
100  Eigen::Vector3f p_eigen = p.getVector3fMap();
101  Eigen::Vector3f foot_point;
102  line.foot(p_eigen, foot_point);
103  output.push_back(foot_point);
104  }
105  }
106 
108  const jsk_recognition_utils::PointPair& a_edge_pair, const jsk_recognition_utils::PointPair& b_edge_pair)
109  {
111  vertices.push_back(a_edge_pair.get<0>());
112  vertices.push_back(a_edge_pair.get<1>());
113  vertices.push_back(b_edge_pair.get<1>());
114  vertices.push_back(b_edge_pair.get<0>());
116  return convex;
117  }
118 
119  // pcl removed the method by 1.13, no harm in defining it ourselves to use below
120 #if __cplusplus >= 201103L
121 #define pcl_isfinite(x) std::isfinite(x)
122 #endif
123 
125  const pcl::PointCloud<pcl::PointXYZRGB>& cloud,
128  {
129  std::vector<int> a_indices, b_indices;
130  for (size_t i = 0; i < cloud.points.size(); i++) {
131  pcl::PointXYZRGB pcl_point = cloud.points[i];
132  if (pcl_isfinite(pcl_point.x) &&
133  pcl_isfinite(pcl_point.y) &&
134  pcl_isfinite(pcl_point.z)) { // we don't care nan points
135  Eigen::Vector3f eigen_point = pcl_point.getVector3fMap();
136  if (polygon_a.distanceSmallerThan(eigen_point, outlier_threshold_)) {
137  a_indices.push_back(i);
138  }
139  if (polygon_b.distanceSmallerThan(eigen_point, outlier_threshold_)) {
140  b_indices.push_back(i);
141  }
142  }
143  }
144  // ...the number of points...?
145  return a_indices.size() + b_indices.size();
146  }
147 
149  const jsk_recognition_utils::Line& axis,
150  const jsk_recognition_utils::PointPair& a_candidates,
151  const jsk_recognition_utils::PointPair& b_candidates)
152  {
153  jsk_recognition_utils::Vertices original_points;
154  original_points.push_back(a_candidates.get<0>());
155  original_points.push_back(a_candidates.get<1>());
156  original_points.push_back(b_candidates.get<0>());
157  original_points.push_back(b_candidates.get<1>());
158  for (size_t i = 0; i < original_points.size(); i++) {
159  Eigen::Vector3f p = original_points[i];
160  ROS_INFO("[foot_point] [%f, %f, %f]", p[0], p[1], p[2]);
161  }
162 
164  for (size_t i = 0; i < original_points.size(); i++) {
165  Eigen::Vector3f foot_point;
166  axis.foot(original_points[i], foot_point);
167  foot_points.push_back(foot_point);
168  }
169  double max_alpha = -DBL_MAX;
170  double min_alpha = DBL_MAX;
171  Eigen::Vector3f max_alpha_point, min_alpha_point;
172 
173  for (size_t i = 0; i < foot_points.size(); i++) {
174  double alpha = axis.computeAlpha(foot_points[i]);
175  if (alpha > max_alpha) {
176  max_alpha = alpha;
177  max_alpha_point = foot_points[i];
178  }
179  if (alpha < min_alpha) {
180  min_alpha = alpha;
181  min_alpha_point = foot_points[i];
182  }
183  }
184  ROS_INFO("min_alpha_point: [%f, %f, %f]", min_alpha_point[0], min_alpha_point[1], min_alpha_point[2]);
185  ROS_INFO("max_alpha_point: [%f, %f, %f]", max_alpha_point[0], max_alpha_point[1], max_alpha_point[2]);
186  return boost::make_tuple(min_alpha_point, max_alpha_point);
187  }
188 
189 
191  const IndicesPair& pair, const CoefficientsPair& coefficients_pair, const double outlier_threshold):
192  CubeHypothesis(pair, coefficients_pair, outlier_threshold)
193  {
194 
195  }
196 
198  const IndicesPair& pair, const CoefficientsPair& coefficients_pair,
199  const double outlier_threshold):
200  CubeHypothesis(pair, coefficients_pair, outlier_threshold), resolution_(10)
201  {
202 
203  }
204 
206  const pcl::PointCloud<pcl::PointXYZRGB>& cloud)
207  {
208  const double dt = (M_PI - 2.0 * min_angle_) / resolution_;
213  if (!line_a->isSameDirection(*line_b)) {
214  line_b = line_b->flip();
215  }
216 
217  const double r2 = line_a->distance(*line_b);
218  const double r = r2 / 2;
219  jsk_recognition_utils::Line::Ptr axis = line_a->midLine(*line_b);
220  Eigen::Vector3f center;
221  axis->getOrigin(center);
222  ROS_INFO("line_a:");
223  line_a->print();
224  ROS_INFO("line_b:");
225  line_b->print();
226  ROS_INFO("axis:");
227  axis->print();
228  ROS_INFO("r: %f", r);
229 
230  // before evaluation, we fix line_a and line_b to be parallel
231  // against line_c and axis.
232  // in order to align line_a and line_b, we compute centroids of the points
233  // on line_a and line_b and rotate the lines around the points.
234  Eigen::Vector3f centroid_a, centroid_b;
235  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_ptr = cloud.makeShared();
236  computeCentroid(cloud_ptr, indices_pair_.get<0>(), centroid_a);
237  computeCentroid(cloud_ptr, indices_pair_.get<1>(), centroid_b);
238  ROS_INFO("centroid_a: [%f, %f, %f]", centroid_a[0], centroid_a[1], centroid_a[2]);
239  ROS_INFO("centroid_b: [%f, %f, %f]", centroid_b[0], centroid_b[1], centroid_b[2]);
240  jsk_recognition_utils::Line::Ptr line_a_aligned = axis->parallelLineOnAPoint(centroid_a);
241  jsk_recognition_utils::Line::Ptr line_b_aligned = axis->parallelLineOnAPoint(centroid_b);
242  ROS_INFO("line_a_aligned:");
243  line_a_aligned->print();
244  ROS_INFO("line_b_aligned:");
245  line_b_aligned->print();
246 
247  jsk_recognition_utils::Vertices line_a_points, line_b_points;
248  getLinePoints(*line_a_aligned, cloud, indices_pair_.get<0>(),
249  line_a_points);
250  getLinePoints(*line_b_aligned, cloud, indices_pair_.get<1>(),
251  line_b_points);
252  jsk_recognition_utils::PointPair line_a_end_points = line_a->findEndPoints(line_a_points);
253  jsk_recognition_utils::PointPair line_b_end_points = line_b->findEndPoints(line_b_points);
254  double max_v = - DBL_MAX;
255  double max_theta;
257  jsk_recognition_utils::PointPair max_line_c_a_points, max_line_c_b_points;
258  for (size_t i = 0; i < resolution_; i++) {
259  ROS_INFO("estimate i: %lu", i);
260  double theta = dt * i + min_angle_;
261  Eigen::Vector3f point_on_x;
262  line_a->foot(center, point_on_x);
263  // 2D local cooridnate: r * cos(theta), r * sin(theta)
264  // convert it according to axis
265  // x // (point_on_x - center)
266  // z // axis
267  Eigen::Vector3f ex = (point_on_x - center).normalized();
268  Eigen::Vector3f ez;
269  axis->getDirection(ez);
270  Eigen::Vector3f ey = ez.cross(ex).normalized();
271  // ey should direct to origin. If not, ex should be flipped
272  if (center.dot(ey) > 0) {
273  ex = -ex;
274  ey = ez.cross(ex).normalized();
275  }
276  Eigen::Vector3f point_on_y = center + r * ey;
277  jsk_recognition_utils::Line::Ptr line_c = axis->parallelLineOnAPoint(point_on_y);
278  // line_a, b, c are almost parallel and these 3 lines make
279  // 2 planes.
280  // ------------------------ line_a
281  // / A /
282  // ----------------------- line_c
283  // \ B \
284  // ----------------------- line_b
285 
286  // in order to evaluate plane A, first we exract the points
287  // which have distance |line_a - line_c| + margin from line_c.
288  // Second, For all those points, count all the points whose distance from
289  // plane A is smaller than margin.
290  // Thrid, we compute the area of the plane A and normalize the value.
291  Eigen::Vector3f line_c_a_min_point, line_c_a_max_point;
292  Eigen::Vector3f line_c_b_min_point, line_c_b_max_point;
293  line_c->foot(line_a_end_points.get<0>(), line_c_a_min_point);
294  line_c->foot(line_a_end_points.get<1>(), line_c_a_max_point);
295  line_c->foot(line_b_end_points.get<0>(), line_c_b_min_point);
296  line_c->foot(line_b_end_points.get<1>(), line_c_b_max_point);
297  jsk_recognition_utils::PointPair line_c_a_end_points = boost::make_tuple(line_c_a_min_point,
298  line_c_a_max_point);
299  jsk_recognition_utils::PointPair line_c_b_end_points = boost::make_tuple(line_c_b_min_point,
300  line_c_b_max_point);
302  line_c_a_end_points);
304  line_c_b_end_points);
305  double v = evaluatePointOnPlanes(cloud, *plane_a, *plane_b);
306  if (max_v < v) {
307  max_v = v;
308  max_theta = theta;
309  max_line_c = line_c;
310  max_line_c_a_points = line_c_a_end_points;
311  max_line_c_b_points = line_c_b_end_points;
312  }
313  }
314  value_ = max_v;
315  // estimate centroid
317  *axis,
318  max_line_c_a_points,
319  max_line_c_b_points);
320  ROS_INFO("end_point: [%f, %f, %f]", axis_end_points.get<0>()[0], axis_end_points.get<0>()[1], axis_end_points.get<0>()[2]);
321  ROS_INFO("end_point: [%f, %f, %f]", axis_end_points.get<1>()[0], axis_end_points.get<1>()[1], axis_end_points.get<1>()[2]);
322  Eigen::Vector3f midpoint
323  = (axis_end_points.get<0>() + axis_end_points.get<1>()) / 2.0;
324  double z_dimension = (axis_end_points.get<0>() - midpoint).norm() * 2;
325  // compute cube
326  ROS_INFO("midpoint: [%f, %f, %f]", midpoint[0], midpoint[1], midpoint[2]);
327  cube_.reset(new jsk_recognition_utils::Cube(midpoint, *line_a_aligned, *line_b_aligned, *max_line_c));
328  std::vector<double> dimensions = cube_->getDimensions();
329  dimensions[2] = z_dimension;
330  cube_->setDimensions(dimensions);
331  }
332 
334  const pcl::PointCloud<PointT>::Ptr cloud,
336  {
337  int num = 0;
338  for (size_t i = 0; i < cloud->points.size(); i++) {
339  PointT p = cloud->points[i];
340  if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
341  Eigen::Vector3f ep = p.getVector3fMap();
342  if (convex->distanceSmallerThan(ep, outlier_threshold_)) {
343  num++;
344  }
345  }
346  }
347  return num;
348  }
349 
351  const pcl::PointCloud<PointT>::Ptr cloud,
352  const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes,
353  std::vector<int>& output_indices)
354  {
355 
356  for (size_t i = 0; i < convexes.size(); i++) {
357  jsk_recognition_utils::ConvexPolygon::Ptr convex = convexes[i];
358  if (true) {
359  // if (convex->area() > convex_area_threshold_ &&
360  // convex->allEdgesLongerThan(convex_edge_threshold_)) {
361  //int inliers = countInliers(cloud, convex);
362  //ROS_INFO("inliers: %d", inliers);
363  //if (inliers > min_inliers_) {
364  if (true) {
365  output_indices.push_back(i);
366  }
367  }
368  }
369  }
370 
371  void EdgebasedCubeFinder::configCallback (Config &config, uint32_t level)
372  {
373  boost::mutex::scoped_lock lock(mutex_);
374  outlier_threshold_ = config.outlier_threshold;
375  min_inliers_ = config.min_inliers;
376  convex_area_threshold_ = config.convex_area_threshold;
377  convex_edge_threshold_ = config.convex_edge_threshold;
378  parallel_edge_distance_min_threshold_ = config.parallel_edge_distance_min_threshold;
379  parallel_edge_distance_max_threshold_ = config.parallel_edge_distance_max_threshold;
380  }
381 
383  {
384  ConnectionBasedNodelet::onInit();
385 
386 
387  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
388  dynamic_reconfigure::Server<Config>::CallbackType f =
389  boost::bind (&EdgebasedCubeFinder::configCallback, this, _1, _2);
390  srv_->setCallback (f);
391 
392 
394  // publishers
396  pub_ = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, "output", 1);
398  = advertise<geometry_msgs::PoseArray>(*pnh_, "output_pose_array", 1);
400  = advertise<visualization_msgs::Marker>(*pnh_, "debug_marker", 1);
401  pub_debug_filtered_cloud_ = advertise<sensor_msgs::PointCloud2>(
402  *pnh_, "debug_filtered_cloud", 1);
404  = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "debug_polygons", 1);
406  = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "debug_clusters", 1);
407 
408  onInitPostProcess();
409  }
410 
412  // message_filters::Synchronizer needs to be called reset
413  // before message_filters::Subscriber is freed.
414  // Calling reset fixes the following error on shutdown of the nodelet:
415  // terminate called after throwing an instance of
416  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
417  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
418  // Also see https://github.com/ros/ros_comm/issues/720 .
419  sync_.reset();
420  }
421 
423  {
425  // subscription
427  sub_input_.subscribe(*pnh_, "input", 1);
428  sub_edges_.subscribe(*pnh_, "input_edges", 1);
429  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
430  sync_->connectInput(sub_input_, sub_edges_);
431  sync_->registerCallback(boost::bind(
433  }
434 
436  {
439  }
440 
442  const CoefficientsPair& pair)
443  {
444  pcl::ModelCoefficients::Ptr coefficients_a = pair.get<0>();
445  pcl::ModelCoefficients::Ptr coefficients_b = pair.get<1>();
448  return line_a->midLine(*line_b);
449  }
450 
451  pcl::PointCloud<EdgebasedCubeFinder::PointT>::Ptr EdgebasedCubeFinder::extractPointCloud(
452  const pcl::PointCloud<PointT>::Ptr cloud,
453  const pcl::PointIndices::Ptr indices)
454  {
455  pcl::PointCloud<PointT>::Ptr ret (new pcl::PointCloud<PointT>);
456  pcl::ExtractIndices<PointT> ex;
457  ex.setInputCloud(cloud);
458  ex.setIndices(indices);
459  ex.filter(*ret);
460  return ret;
461  }
462 
465  const pcl::PointCloud<PointT>::Ptr cloud)
466  {
468  for (size_t i = 0; i < cloud->points.size(); i++) {
469  PointT p = cloud->points[i];
470  Eigen::Vector3f eigen_p = p.getVector3fMap();
471  Eigen::Vector3f foot;
472  line.foot(eigen_p, foot);
473  points.push_back(foot);
474  }
475  return line.findEndPoints(points);
476  }
477 
479  const pcl::PointCloud<PointT>::Ptr cloud,
480  const CoefficientsPair& coefficients_pair,
481  const IndicesPair& indices_pair)
482  {
483  pcl::ModelCoefficients::Ptr coefficients_a = coefficients_pair.get<0>();
484  pcl::ModelCoefficients::Ptr coefficients_b = coefficients_pair.get<1>();
485  pcl::PointIndices::Ptr indices_a = indices_pair.get<0>();
486  pcl::PointIndices::Ptr indices_b = indices_pair.get<1>();
487 
488  pcl::PointCloud<PointT>::Ptr cloud_a = extractPointCloud(cloud, indices_a);
489  pcl::PointCloud<PointT>::Ptr cloud_b = extractPointCloud(cloud, indices_b);
490 
493  jsk_recognition_utils::PointPair a_min_max = minMaxPointOnLine(*line_a, cloud_a);
494  jsk_recognition_utils::PointPair b_min_max = minMaxPointOnLine(*line_b, cloud_b);
496  vertices.push_back(a_min_max.get<0>());
497  vertices.push_back(a_min_max.get<1>());
498  vertices.push_back(b_min_max.get<1>());
499  vertices.push_back(b_min_max.get<0>());
501  return ret;
502  }
503 
505  const std::vector<IndicesPair>& pairs,
506  const std::vector<CoefficientsPair>& coefficients_pair,
507  std::vector<IndicesPair>& filtered_indices_pairs,
508  std::vector<CoefficientsPair>& filtered_coefficients_pairs)
509  {
510  for (size_t i = 0; i < coefficients_pair.size(); i++) {
511  CoefficientsPair coefficients = coefficients_pair[i];
512  pcl::ModelCoefficients::Ptr coefficients_a = coefficients_pair[i].get<0>();
513  pcl::ModelCoefficients::Ptr coefficients_b = coefficients_pair[i].get<1>();
516 
517  // force to align two lines
518  jsk_recognition_utils::Line::Ptr axis = line_a->midLine(*line_b);
519  Eigen::Vector3f origin_a, origin_b;
520  line_a->getOrigin(origin_a);
521  line_b->getOrigin(origin_b);
522  jsk_recognition_utils::Line::Ptr line_a_aligned = axis->parallelLineOnAPoint(origin_a);
523  jsk_recognition_utils::Line::Ptr line_b_aligned = axis->parallelLineOnAPoint(origin_b);
524  Eigen::Vector3f distance_vector;
525  line_a_aligned->parallelLineNormal(*line_b_aligned, distance_vector);
526  double distance = distance_vector.norm();
527  //double distance = line_a_aligned->distance(*line_b_aligned);
528  ROS_INFO("d: %f", distance);
531  filtered_indices_pairs.push_back(pairs[i]);
532  filtered_coefficients_pairs.push_back(coefficients);
533  }
534  }
535  }
536 
537  //pcl::PointCloud<EdgebasedCubeFinder::PointT>::Ptr
538  pcl::PointIndices::Ptr
541  const CoefficientsPair& edge_coefficients_pair,
542  const pcl::PointCloud<PointT>::Ptr cloud)
543  {
544  // extract the points which can be projected onto the convex.
545  pcl::PointIndices::Ptr indices(new pcl::PointIndices);
546  jsk_recognition_utils::ConvexPolygon::Ptr magnified_convex = convex->magnify(1.1);
547  pcl::PointCloud<PointT>::Ptr ret (new pcl::PointCloud<PointT>);
548  for (size_t i = 0; i < cloud->points.size(); i++) {
549  PointT p = cloud->points[i];
550  if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
551  Eigen::Vector3f ep = p.getVector3fMap();
552  Eigen::Vector3f foot;
553  magnified_convex->projectOnPlane(ep, foot);
554  if (magnified_convex->isInside(foot) && convex->distanceSmallerThan(ep, outlier_threshold_)) {
555  //if (magnified_convex->isInside(foot) && (ep - foot).norm()) {
556  //NODELET_INFO("distance: %f", (ep - foot).norm());
557  indices->indices.push_back(i);
558  }
559  }
560  }
561  return indices;
562  }
563 
566  const pcl::PointCloud<PointT>::Ptr filtered_cloud,
567  pcl::PointIndices::Ptr output_inliers,
568  pcl::ModelCoefficients::Ptr output_coefficients)
569  {
570  Eigen::Vector3f normal = convex->getNormal();
571  pcl::SACSegmentation<PointT> seg;
572  seg.setOptimizeCoefficients (true);
573  seg.setModelType (pcl::SACMODEL_PERPENDICULAR_PLANE);
574  seg.setMethodType (pcl::SAC_RANSAC);
575  seg.setDistanceThreshold (outlier_threshold_);
576  seg.setInputCloud(filtered_cloud);
577  seg.setMaxIterations (10000);
578  seg.setAxis(normal);
579  seg.setEpsAngle(pcl::deg2rad(10.0));
580  seg.segment (*output_inliers, *output_coefficients);
581  }
582 
585  const CoefficientsPair& edge_coefficients,
586  const pcl::PointCloud<PointT>::Ptr filtered_cloud,
587  pcl::PointIndices::Ptr output_inliers,
588  pcl::ModelCoefficients::Ptr output_coefficients)
589  {
590  Eigen::Vector3f normal_a = convex->getNormal();
592  Eigen::Vector3f normal_b;
593  mid_line->getDirection(normal_b);
594  Eigen::Vector3f normal = normal_a.cross(normal_b);
595  pcl::SACSegmentation<PointT> seg;
596  seg.setOptimizeCoefficients (true);
597  seg.setModelType (pcl::SACMODEL_PERPENDICULAR_PLANE);
598  seg.setMethodType (pcl::SAC_RANSAC);
599  seg.setDistanceThreshold (outlier_threshold_);
600  seg.setInputCloud(filtered_cloud);
601  seg.setMaxIterations (10000);
602  seg.setAxis(normal);
603  seg.setEpsAngle(pcl::deg2rad(5.0));
604  seg.segment (*output_inliers, *output_coefficients);
605  }
606 
608  const pcl::PointCloud<EdgebasedCubeFinder::PointT>::Ptr cloud,
609  const IndicesCoefficientsTriple& indices_coefficients_triple,
610  pcl::PointCloud<EdgebasedCubeFinder::PointT>::Ptr points_on_edge)
611  {
612  Eigen::Vector3f ex, ey, ez;
613  CoefficientsTriple coefficients_triple
614  = indices_coefficients_triple.get<1>();
615  IndicesTriple indices_triple
616  = indices_coefficients_triple.get<0>();
617  // do we need to align lines...??
619  = jsk_recognition_utils::Line::fromCoefficients(coefficients_triple.get<0>()->values);
621  = jsk_recognition_utils::Line::fromCoefficients(coefficients_triple.get<1>()->values);
623  = jsk_recognition_utils::Line::fromCoefficients(coefficients_triple.get<2>()->values);
624  // force to align
625  if (!mid_line->isSameDirection(*line_a)) {
626  line_a = line_a->flip();
627  }
628  if (!mid_line->isSameDirection(*line_b)) {
629  line_b = line_b->flip();
630  }
631  jsk_recognition_utils::Line::Ptr axis = line_a->midLine(*line_b);
632 
633  pcl::PointCloud<PointT>::Ptr point_on_a
634  = extractPointCloud(cloud,
635  indices_triple.get<1>());
636  pcl::PointCloud<PointT>::Ptr point_on_b
637  = extractPointCloud(cloud,
638  indices_triple.get<2>());
639  pcl::PointCloud<PointT>::Ptr point_on_c
640  = extractPointCloud(cloud,
641  indices_triple.get<0>());
642  Eigen::Vector4f a_centroid4, b_centroid4, c_centroid4;
643  Eigen::Vector3f a_centroid, b_centroid, c_centroid;
644  pcl::compute3DCentroid(*point_on_a, a_centroid4);
645  pcl::compute3DCentroid(*point_on_b, b_centroid4);
646  pcl::compute3DCentroid(*point_on_c, c_centroid4);
647  jsk_recognition_utils::pointFromVectorToVector<Eigen::Vector4f, Eigen::Vector3f>(
648  a_centroid4, a_centroid);
649  jsk_recognition_utils::pointFromVectorToVector<Eigen::Vector4f, Eigen::Vector3f>(
650  b_centroid4, b_centroid);
651  jsk_recognition_utils::pointFromVectorToVector<Eigen::Vector4f, Eigen::Vector3f>(
652  c_centroid4, c_centroid);
653 
654  jsk_recognition_utils::Line::Ptr line_a_aligned = axis->parallelLineOnAPoint(a_centroid);
655  jsk_recognition_utils::Line::Ptr line_b_aligned = axis->parallelLineOnAPoint(b_centroid);
656  jsk_recognition_utils::Line::Ptr mid_line_aligned = axis->parallelLineOnAPoint(c_centroid);
657  //Line::Ptr axis_aligned = axis->parallelLineOnAPoint(c_centroid);
658  pcl::PointCloud<PointT>::Ptr all_points(new pcl::PointCloud<PointT>);
659  *all_points = *point_on_a + *point_on_b;
660  *all_points = *all_points + *point_on_c;
661  *points_on_edge = *all_points;
662 
663  // PointT a_centroid_p, b_centroid_p, c_centroid_p;
664  // a_centroid_p.x = a_centroid[0];
665  // a_centroid_p.y = a_centroid[1];
666  // a_centroid_p.z = a_centroid[2];
667  // b_centroid_p.x = b_centroid[0];
668  // b_centroid_p.y = b_centroid[1];
669  // b_centroid_p.z = b_centroid[2];
670  // c_centroid_p.x = c_centroid[0];
671  // c_centroid_p.y = c_centroid[1];
672  // c_centroid_p.z = c_centroid[2];
673  // points_on_edge->points.push_back(a_centroid_p);
674  // points_on_edge->points.push_back(b_centroid_p);
675  // points_on_edge->points.push_back(c_centroid_p);
676 
677  jsk_recognition_utils::PointPair min_max_points = minMaxPointOnLine(*axis, all_points);
678  PointT min_point, max_point;
679  // min_point.x = min_max_points.get<0>()[0];
680  // min_point.y = min_max_points.get<0>()[1];
681  // min_point.z = min_max_points.get<0>()[2];
682  // max_point.x = min_max_points.get<1>()[0];
683  // max_point.y = min_max_points.get<1>()[1];
684  // max_point.z = min_max_points.get<1>()[2];
685  // points_on_edge->points.push_back(min_point);
686  // points_on_edge->points.push_back(max_point);
687  Eigen::Vector3f center_point
688  = (min_max_points.get<0>() + min_max_points.get<1>()) / 2.0;
689  double z_width = (min_max_points.get<0>() - min_max_points.get<1>()).norm();
690  mid_line_aligned->getDirection(ez);
691  mid_line_aligned->parallelLineNormal(*line_a_aligned, ex);
692  mid_line_aligned->parallelLineNormal(*line_b_aligned, ey);
693 
694  double x_width = ex.norm();
695  double y_width = ey.norm();
696 
697  ex.normalize();
698  ey.normalize();
699  ez.normalize();
700 
701  ROS_INFO("ex: [%f, %f, %f]", ex[0], ex[1], ex[2]);
702  ROS_INFO("ey: [%f, %f, %f]", ey[0], ey[1], ey[2]);
703  ROS_INFO("ez: [%f, %f, %f]", ez[0], ez[1], ez[2]);
704 
705  if (ex.cross(ey).dot(ez) < 0) {
706  ez = -ez;
707  }
708 
709  Eigen::Quaternionf rot = jsk_recognition_utils::rotFrom3Axis(ex, ey, ez);
710  std::vector<double> dimensions;
711  dimensions.push_back(x_width);
712  dimensions.push_back(y_width);
713  dimensions.push_back(z_width);
714  jsk_recognition_utils::Cube::Ptr ret (new jsk_recognition_utils::Cube(center_point, rot, dimensions));
715  return ret;
716  }
717 
719  const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
720  const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr& input_edges)
721  {
722  boost::mutex::scoped_lock lock(mutex_);
723  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
724  pcl::PointCloud<PointT>::Ptr all_filtered_cloud (new pcl::PointCloud<PointT>);
725  pcl::fromROSMsg(*input_cloud, *cloud);
726  visualization_msgs::Marker marker;
727  jsk_recognition_msgs::PolygonArray polygon_array;
728  geometry_msgs::PoseArray pose_array;
729  jsk_recognition_msgs::BoundingBoxArray box_array;
730  box_array.header = input_cloud->header;
731  pose_array.header = input_cloud->header;
732  std::vector<jsk_recognition_utils::Cube::Ptr> cubes;
733  std::vector<pcl::PointIndices::Ptr> candidate_cluster_indices;
734  for (size_t i = 0; i < input_edges->edge_groups.size(); i++) {
735  jsk_recognition_msgs::ParallelEdge parallel_edge = input_edges->edge_groups[i];
736  std::vector<pcl::PointIndices::Ptr> edges
738  parallel_edge.cluster_indices);
739  std::vector<pcl::ModelCoefficients::Ptr> coefficients
741  parallel_edge.coefficients);
742  std::vector<IndicesCoefficientsTriple> triples
743  = tripleIndicesAndCoefficients(edges, coefficients);
744  std::vector<IndicesCoefficientsTriple> perpendicular_triples
746  if (perpendicular_triples.size() > 0) {
747  // buildup cube instance...
748  pcl::PointCloud<PointT>::Ptr points_on_edges(new pcl::PointCloud<PointT>);
749  pcl_conversions::toPCL(input_cloud->header, points_on_edges->header);
750  for (size_t j = 0; j < perpendicular_triples.size(); j++) {
751  pcl::PointCloud<PointT>::Ptr points_on_edge(new pcl::PointCloud<PointT>);
753  cloud,
754  perpendicular_triples[j],
755  points_on_edge);
756  *points_on_edges = *points_on_edges + *points_on_edge;
757  cubes.push_back(cube);
758  }
759 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
760  pub_debug_filtered_cloud_.publish(*points_on_edges);
761 #else
762  pub_debug_filtered_cloud_.publish(points_on_edges);
763 #endif
764  }
765  }
766 
767  if (cubes.size() > 0) {
768  for (size_t i = 0; i < cubes.size(); i++) {
769  // publish cubes
770  jsk_recognition_msgs::BoundingBox ros_box = cubes[i]->toROSMsg();
771  ros_box.header = input_cloud->header;
772  box_array.boxes.push_back(ros_box);
773  pose_array.poses.push_back(ros_box.pose);
774  }
775  pub_.publish(box_array);
776  pub_pose_array_.publish(pose_array);
777  }
778  }
779 
781  const Eigen::Vector3f& a,
782  const Eigen::Vector3f& b)
783  {
784  double dot = a.normalized().dot(b.normalized());
785  if (fabs(dot) >= 1.0) {
786  return false;
787  }
788  else {
789  double theta = fabs(acos(dot));
790  NODELET_INFO("theta: %f", pcl::rad2deg(theta));
791  if (fabs(theta - M_PI / 2.0) < pcl::deg2rad(20.0)) {
792  return true;
793  }
794  else {
795  return false;
796  }
797  }
798  }
799 
801  const jsk_recognition_utils::Line& edge_a,
802  const jsk_recognition_utils::Line& edge_b,
803  const jsk_recognition_utils::Line& edge_c)
804  {
805  Eigen::Vector3f a_b_normal, a_c_normal;
806  edge_a.parallelLineNormal(edge_b, a_b_normal);
807  edge_a.parallelLineNormal(edge_c, a_c_normal);
808  if (isPerpendicularVector(a_b_normal, a_c_normal)) {
809  return A_PERPENDICULAR;
810  }
811  else {
812  Eigen::Vector3f b_a_normal, b_c_normal;
813  edge_b.parallelLineNormal(edge_a, b_a_normal);
814  edge_b.parallelLineNormal(edge_c, b_c_normal);
815  if (isPerpendicularVector(b_a_normal, b_c_normal)) {
816  return B_PERPENDICULAR;
817  }
818  else {
819  Eigen::Vector3f c_a_normal, c_b_normal;
820  edge_c.parallelLineNormal(edge_a, c_a_normal);
821  edge_c.parallelLineNormal(edge_b, c_b_normal);
822  if (isPerpendicularVector(c_a_normal, c_b_normal)) {
823  return C_PERPENDICULAR;
824  }
825  else {
826  return NOT_PERPENDICULAR;
827  }
828  }
829  }
830  }
831 
832  std::vector<IndicesCoefficientsTriple>
834  const std::vector<IndicesCoefficientsTriple>& triples)
835  {
836  std::vector<IndicesCoefficientsTriple> ret;
837  for (size_t i = 0; i < triples.size(); i++) {
838  pcl::ModelCoefficients::Ptr a_coefficients
839  = triples[i].get<1>().get<0>();
840  pcl::ModelCoefficients::Ptr b_coefficients
841  = triples[i].get<1>().get<1>();
842  pcl::ModelCoefficients::Ptr c_coefficients
843  = triples[i].get<1>().get<2>();
845  = jsk_recognition_utils::Line::fromCoefficients(a_coefficients->values);
847  = jsk_recognition_utils::Line::fromCoefficients(b_coefficients->values);
849  = jsk_recognition_utils::Line::fromCoefficients(c_coefficients->values);
850  // check if these three are perpendicular or not
851  EdgeRelation relation = perpendicularEdgeTriple(*edge_a,
852  *edge_b,
853  *edge_c);
854  if (relation != NOT_PERPENDICULAR) {
855  // rearrange
856  if (relation == A_PERPENDICULAR) {
857  ret.push_back(triples[i]);
858  }
859  else if (relation == B_PERPENDICULAR) {
860  IndicesCoefficientsTriple new_triple
861  = boost::make_tuple(
862  boost::make_tuple(triples[i].get<0>().get<1>(),
863  triples[i].get<0>().get<0>(),
864  triples[i].get<0>().get<2>()),
865  boost::make_tuple(
866  triples[i].get<1>().get<1>(),
867  triples[i].get<1>().get<0>(),
868  triples[i].get<1>().get<2>()));
869  ret.push_back(new_triple);
870  }
871  else if (relation == C_PERPENDICULAR) {
872  IndicesCoefficientsTriple new_triple
873  = boost::make_tuple(
874  boost::make_tuple(triples[i].get<0>().get<2>(),
875  triples[i].get<0>().get<0>(),
876  triples[i].get<0>().get<1>()),
877  boost::make_tuple(
878  triples[i].get<1>().get<2>(),
879  triples[i].get<1>().get<0>(),
880  triples[i].get<1>().get<1>()));
881  ret.push_back(new_triple);
882  }
883  }
884  }
885  return ret;
886  }
887 
889  const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
890  const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr& input_edges)
891  {
892  boost::mutex::scoped_lock lock(mutex_);
893  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
894  pcl::PointCloud<PointT>::Ptr all_filtered_cloud (new pcl::PointCloud<PointT>);
895  pcl::fromROSMsg(*input_cloud, *cloud);
896  visualization_msgs::Marker marker;
897  jsk_recognition_msgs::PolygonArray polygon_array;
898  std::vector<pcl::PointIndices::Ptr> candidate_cluster_indices;
899 
900  polygon_array.header = input_cloud->header;
901  marker.pose.orientation.w = 1.0;
902  marker.color.a = 1.0;
903  marker.color.r = 1.0;
904  marker.header = input_cloud->header;
905  marker.scale.x = 0.01;
906  marker.type = visualization_msgs::Marker::LINE_LIST;
907  NODELET_INFO("%lu parallel edge groups", input_edges->edge_groups.size());
908  geometry_msgs::PoseArray pose_array;
909  pose_array.header = input_cloud->header;
910  jsk_recognition_msgs::BoundingBoxArray ros_output;
911  ros_output.header = input_cloud->header;
912 
913  for (size_t i = 0; i < input_edges->edge_groups.size(); i++) {
914  jsk_recognition_msgs::ParallelEdge parallel_edge = input_edges->edge_groups[i];
915 
916  if (parallel_edge.cluster_indices.size() <= 1) {
917  NODELET_ERROR("parallel edge group has only %lu edges",
918  parallel_edge.cluster_indices.size());
919  continue;
920  }
921  NODELET_INFO("%lu parallel edge groups has %lu edges",
922  i, parallel_edge.cluster_indices.size());
924  // first convert all the pcl_msgs/PointIndices to pcl::PointIndices
926  std::vector<pcl::PointIndices::Ptr> edges
928  parallel_edge.cluster_indices);
929  std::vector<pcl::ModelCoefficients::Ptr> coefficients
931  parallel_edge.coefficients);
932 
933  std::vector<IndicesPair> pairs = combinateIndices(edges);
934  std::vector<CoefficientsPair> coefficients_pair
935  = combinateCoefficients(coefficients);
936  std::vector<IndicesPair> filtered_indices_pairs;
937  std::vector<CoefficientsPair> filtered_coefficients_pairs;
938 
939  filtered_indices_pairs = pairs;
940  filtered_coefficients_pairs = coefficients_pair;
941  // filterPairsBasedOnParallelEdgeDistances(
942  // pairs, coefficients_pair,
943  // filtered_indices_pairs, filtered_coefficients_pairs);
944 
945  // convex based filtering...
946  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes;
947  for (size_t j = 0; j < filtered_coefficients_pairs.size(); j++) {
949  = convexFromPairs(cloud, filtered_coefficients_pairs[j],
950  pairs[j]);
951  convexes.push_back(convex);
952  }
953  std::vector<int> filtered_indices;
954  filterBasedOnConvex(cloud, convexes, filtered_indices);
955 
956  pcl::PointIndices::Ptr filtered_cube_candidate_indices(new pcl::PointIndices);
957  for (size_t j = 0; j < filtered_indices.size(); j++) {
958  int index = filtered_indices[j];
959  jsk_recognition_utils::ConvexPolygon::Ptr target_convex = convexes[index];
960  IndicesPair target_edge_indices_pair
961  = filtered_indices_pairs[index];
962  CoefficientsPair target_edge_coefficients_pair
963  = filtered_coefficients_pairs[index];
964  // 1. roughly segment the points around the plane
965  //pcl::PointCloud<PointT>::Ptr filtered_cloud
966  pcl::PointIndices::Ptr filtered_indices
968  target_convex, target_edge_coefficients_pair, cloud);
969  // *filtered_cube_candidate_indices
970  // = *filtered_indices + *filtered_cube_candidate_indices;
971  filtered_cube_candidate_indices
972  = jsk_recognition_utils::addIndices(*filtered_cube_candidate_indices,
973  *filtered_indices);
974 
975  // ROS_INFO("%lu -> %lu", cloud->points.size(), filtered_cloud->points.size());
976  // *all_filtered_cloud = *all_filtered_cloud + *filtered_cloud;
977  // // 2. estimate a plane parallel to the convex using RANSAC
978  // pcl::ModelCoefficients::Ptr
979  // parallel_plane_coefficients (new pcl::ModelCoefficients);
980  // pcl::PointIndices::Ptr
981  // parallel_plane_inliers (new pcl::PointIndices);
982 
983  // estimateParallelPlane(target_convex, filtered_cloud,
984  // parallel_plane_inliers,
985  // parallel_plane_coefficients);
986  // if (parallel_plane_inliers->indices.size() > 0) {
987  // jsk_recognition_utils::ConvexPolygon::Ptr parallel_convex
988  // = jsk_recognition_utils::convexFromCoefficientsAndInliers<PointT>(
989  // filtered_cloud,
990  // parallel_plane_inliers,
991  // parallel_plane_coefficients);
992  // if (parallel_convex) {
993  // pcl::ModelCoefficients::Ptr
994  // perpendicular_plane_coefficients (new pcl::ModelCoefficients);
995  // pcl::PointIndices::Ptr
996  // perpendicular_plane_inliers (new pcl::PointIndices);
997  // estimatePerpendicularPlane(parallel_convex,
998  // target_edge_coefficients_pair,
999  // filtered_cloud,
1000  // perpendicular_plane_inliers,
1001  // perpendicular_plane_coefficients);
1002  // if (perpendicular_plane_inliers->indices.size() > 0) {
1003  // jsk_recognition_utils::ConvexPolygon::Ptr perpendicular_convex
1004  // = jsk_recognition_utils::convexFromCoefficientsAndInliers<PointT>(
1005  // filtered_cloud,
1006  // perpendicular_plane_inliers,
1007  // perpendicular_plane_coefficients);
1008  // if (perpendicular_convex) {
1009  // if (perpendicular_convex->angle(*parallel_convex) < pcl::deg2rad(10.0)) {
1010  // geometry_msgs::PolygonStamped ros_polygon;
1011  // ros_polygon.header = input_cloud->header;
1012  // ros_polygon.polygon = parallel_convex->toROSMsg();
1013  // polygon_array.polygons.push_back(ros_polygon);
1014  // geometry_msgs::PolygonStamped ros_polygon2;
1015  // ros_polygon2.header = input_cloud->header;
1016  // ros_polygon2.polygon = perpendicular_convex->toROSMsg();
1017  // polygon_array.polygons.push_back(ros_polygon2);
1018  // }
1019  // }
1020  // }
1021  // }
1022  // }
1023  // if (parallel_plane) {
1024  // // 3. estimate a plane perpendicular to the convex using RANSAC
1025  // pcl::ModelCoefficients::Ptr perpendicular_plane
1026  // = estimatePerpendicularPlane(convex, filtered_cloud);
1027  // if (perpendicular_plane) {
1028  // // success to estimate, it's cube
1029  // Cube::Ptr cube
1030  // = makeupCubeResult();
1031  // cubes.push_back(cube);
1032  // }
1033  // else {
1034  // // failed to estimate perpendicular plane
1035  // ROS_INFO("failed to estimate perpendicular plane");
1036  // }
1037  // }
1038  // else {
1039  // // failed to estimate parallel plane
1040  // ROS_INFO("failed to estimate parallel plane");
1041  // }
1042 // }
1043 
1044  // for (size_t j = 0; j < filtered_indices.size(); j++) {
1045  // int pair_index = filtered_indices[j];
1046  // jsk_recognition_utils::ConvexPolygon::Ptr convex = convexes[filtered_indices[j]];
1047 
1048  // Vertices vs = convex->getVertices();
1049  // for (size_t k = 0; k < vs.size(); k++) {
1050  // Eigen::Vector3f A, B;
1051  // Eigen::Vector3d Ad, Bd;
1052  // A = vs[k];
1053  // if (k + 1 != vs.size()) {
1054  // B = vs[k + 1];
1055  // }
1056  // else {
1057  // B = vs[0];
1058  // }
1059  // geometry_msgs::Point AP, BP;
1060  // convertEigenVector(A, Ad);
1061  // convertEigenVector(B, Bd);
1062  // tf::pointEigenToMsg(Ad, AP);
1063  // tf::pointEigenToMsg(Bd, BP);
1064  // marker.points.push_back(AP);
1065  // marker.points.push_back(BP);
1066  // std_msgs::ColorRGBA green;
1067  // green.a = 1.0; green.g = 1.0;
1068  // marker.colors.push_back(green);
1069  // marker.colors.push_back(green);
1070  // }
1071  }
1072  candidate_cluster_indices.push_back(filtered_cube_candidate_indices);
1073 
1074  // estimate cube
1075  pcl::PointIndices::Ptr first_inliers(new pcl::PointIndices);
1076  pcl::ModelCoefficients::Ptr first_coefficients(new pcl::ModelCoefficients);
1079  cloud,
1080  filtered_cube_candidate_indices,
1081  first_coefficients,
1082  first_inliers);
1083  if (first_polygon) {
1084  geometry_msgs::PolygonStamped first_polygon_ros;
1085  first_polygon_ros.polygon = first_polygon->toROSMsg();
1086  first_polygon_ros.header = input_cloud->header;
1087  polygon_array.polygons.push_back(first_polygon_ros);
1088  }
1089  // std::vector<CubeHypothesis::Ptr> hypothesis_list;
1090  // NODELET_INFO("building hypothesis");
1091  // NODELET_INFO("pair size: %lu", pairs.size());
1092  // for (size_t j = 0; j < pairs.size(); j++) {
1093  // NODELET_INFO("j -> %lu", j);
1094  // IndicesPair pair = pairs[j];
1095  // CoefficientsPair cpair = coefficients_pair[j];
1096  // PlanarCubeHypothesis::Ptr
1097  // planar_hypothesis (new PlanarCubeHypothesis(
1098  // pair, cpair, outlier_threshold_));
1099  // DiagnoalCubeHypothesis::Ptr
1100  // diagnoal_hypothesis (new DiagnoalCubeHypothesis(
1101  // pair, cpair, outlier_threshold_));
1102  // //hypothesis_list.push_back(planar_hypothesis);
1103  // hypothesis_list.push_back(diagnoal_hypothesis);
1104  // }
1105  // NODELET_INFO("estimating hypothesis");
1106  // for (size_t j = 0; j < hypothesis_list.size(); j++) {
1107  // hypothesis_list[j]->estimate(*cloud);
1108  // }
1109  // // find max evaluated
1110  // NODELET_INFO("find max hypothesis");
1111  // CubeHypothesis::Ptr max_hypothesis;
1112  // double max_eval = -DBL_MAX;
1113  // for (size_t i = 0; i < hypothesis_list.size(); i++) {
1114  // if (max_eval < hypothesis_list[i]->getValue()) {
1115  // max_eval = hypothesis_list[i]->getValue();
1116  // max_hypothesis = hypothesis_list[i];
1117  // }
1118  // }
1119  // NODELET_INFO("convert to ros msg");
1120  // BoundingBox msg = max_hypothesis->getCube()->toROSMsg();
1121  // msg.header = input_cloud->header;
1122  // ros_output.boxes.push_back(msg);
1123  // pose_array.poses.push_back(msg.pose);
1124  }
1125  pub_.publish(ros_output);
1126  pub_pose_array_.publish(pose_array);
1127  pub_debug_marker_.publish(marker);
1128  sensor_msgs::PointCloud2 ros_cloud;
1129  pcl::toROSMsg(*all_filtered_cloud, ros_cloud);
1130  ros_cloud.header = input_cloud->header;
1132  pub_debug_polygons_.publish(polygon_array);
1133 
1134  // convert std::vector<pcl::PointIndices::Ptr> to ClusterPointIndices
1135  jsk_recognition_msgs::ClusterPointIndices ros_cluster_indices;
1136  ros_cluster_indices.header = input_cloud->header;
1137  for (size_t i = 0; i < candidate_cluster_indices.size(); i++) {
1138  PCLIndicesMsg indices_msg;
1139  indices_msg.header = input_cloud->header;
1140  indices_msg.indices = candidate_cluster_indices[i]->indices;
1141  ros_cluster_indices.cluster_indices.push_back(indices_msg);
1142  }
1143  pub_debug_clusers_.publish(ros_cluster_indices);
1144  }
1145 
1146  std::vector<IndicesCoefficientsTriple>
1148  const std::vector<pcl::PointIndices::Ptr>& indices,
1149  const std::vector<pcl::ModelCoefficients::Ptr>& coefficients)
1150  {
1151  if (indices.size() != coefficients.size()) {
1152  NODELET_ERROR("size of indices and coefficients are not same");
1153  return std::vector<IndicesCoefficientsTriple>();
1154  }
1155 
1156  if (indices.size() <= 2 && coefficients.size() <= 2) {
1157  NODELET_WARN("[EdgebasedCubeFinder::tripleIndicesAndCoefficients] no enough canddiates");
1158  return std::vector<IndicesCoefficientsTriple>();
1159  }
1160  std::vector<IndicesCoefficientsTriple> ret;
1161  for (size_t i = 0; i < indices.size() - 2; i++) {
1162  for (size_t j = i + 1; j < indices.size() - 1; j++) {
1163  for (size_t k = j + 1; k < indices.size(); k++) {
1164  IndicesTriple indices_triple
1165  = boost::make_tuple(indices[i],
1166  indices[j],
1167  indices[k]);
1168  CoefficientsTriple coefficients_triple
1169  = boost::make_tuple(coefficients[i],
1170  coefficients[j],
1171  coefficients[k]);
1172  IndicesCoefficientsTriple indices_coefficients_triple
1173  = boost::make_tuple(indices_triple,
1174  coefficients_triple);
1175  ret.push_back(indices_coefficients_triple);
1176  }
1177  }
1178  }
1179  return ret;
1180  }
1181 
1183  const pcl::PointCloud<PointT>::Ptr cloud,
1184  const pcl::PointIndices::Ptr indices,
1185  pcl::ModelCoefficients::Ptr coefficients,
1186  pcl::PointIndices::Ptr inliers)
1187  {
1189  // RANSAC
1191  pcl::SACSegmentation<PointT> seg;
1192  seg.setOptimizeCoefficients (true);
1193  seg.setModelType (pcl::SACMODEL_PLANE);
1194  seg.setMethodType (pcl::SAC_RANSAC);
1195  seg.setInputCloud(cloud);
1196  seg.setIndices(indices);
1197  seg.setDistanceThreshold(0.003);
1198  seg.segment(*inliers, *coefficients);
1200  // project points to the plane
1202  if (inliers->indices.size() > 0) {
1203  return jsk_recognition_utils::convexFromCoefficientsAndInliers<PointT>(
1204  cloud, inliers, coefficients);
1205  }
1206  else {
1208  }
1209  }
1210 
1211  std::vector<IndicesPair> EdgebasedCubeFinder::combinateIndices(
1212  const std::vector<pcl::PointIndices::Ptr>& indices)
1213  {
1214  std::vector<IndicesPair> ret;
1215  for(size_t i = 0; i < indices.size() - 1; i++) {
1216  for (size_t j = i + 1; j < indices.size(); j++) {
1217  IndicesPair pair = boost::make_tuple(indices[i],
1218  indices[j]);
1219  ret.push_back(pair);
1220  }
1221  }
1222  return ret;
1223  }
1224 
1225  std::vector<CoefficientsPair> EdgebasedCubeFinder::combinateCoefficients(
1226  const std::vector<pcl::ModelCoefficients::Ptr>& coefficients)
1227  {
1228  std::vector<CoefficientsPair> ret;
1229  for(size_t i = 0; i < coefficients.size() - 1; i++) {
1230  for (size_t j = i + 1; j < coefficients.size(); j++) {
1231  CoefficientsPair pair = boost::make_tuple(coefficients[i],
1232  coefficients[j]);
1233  ret.push_back(pair);
1234  }
1235  }
1236  return ret;
1237  }
1238 }
1239 
1242 
jsk_pcl_ros::DiagnoalCubeHypothesis::resolution_
int resolution_
Definition: edgebased_cube_finder.h:184
extract_top_polygon_likelihood.ex
ex
Definition: extract_top_polygon_likelihood.py:51
rot
rot
jsk_pcl_ros::CoefficientsPair
boost::tuple< pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr > CoefficientsPair
Definition: edgebased_cube_finder.h:102
NODELET_ERROR
#define NODELET_ERROR(...)
jsk_pcl_ros::EdgebasedCubeFinder::minMaxPointOnLine
virtual jsk_recognition_utils::PointPair minMaxPointOnLine(const jsk_recognition_utils::Line &line, const pcl::PointCloud< PointT >::Ptr cloud)
Definition: edgebased_cube_finder_nodelet.cpp:495
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
jsk_pcl_ros::EdgebasedCubeFinder::pub_debug_polygons_
ros::Publisher pub_debug_polygons_
Definition: edgebased_cube_finder.h:324
_2
boost::arg< 2 > _2
jsk_recognition_utils::ConvexPolygon
pcl_conversions::convertToPCLModelCoefficients
std::vector< pcl::ModelCoefficients::Ptr > convertToPCLModelCoefficients(const std::vector< PCLModelCoefficientMsg > &coefficients)
jsk_pcl_ros::EdgebasedCubeFinder::convex_edge_threshold_
double convex_edge_threshold_
Definition: edgebased_cube_finder.h:332
jsk_pcl_ros::CubeHypothesis::value_
double value_
Definition: edgebased_cube_finder.h:152
jsk_pcl_ros::CubeHypothesis::buildConvexPolygon
virtual jsk_recognition_utils::ConvexPolygon::Ptr buildConvexPolygon(const jsk_recognition_utils::PointPair &a_edge_pair, const jsk_recognition_utils::PointPair &b_edge_pair)
Definition: edgebased_cube_finder_nodelet.cpp:139
boost::shared_ptr< ConvexPolygon >
jsk_pcl_ros::EdgebasedCubeFinder::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: edgebased_cube_finder.h:318
i
int i
jsk_pcl_ros::CubeHypothesis::evaluatePointOnPlanes
virtual double evaluatePointOnPlanes(const pcl::PointCloud< pcl::PointXYZRGB > &cloud, jsk_recognition_utils::ConvexPolygon &polygon_a, jsk_recognition_utils::ConvexPolygon &polygon_b)
Definition: edgebased_cube_finder_nodelet.cpp:156
jsk_pcl_ros::EdgebasedCubeFinder::cubeFromIndicesAndCoefficients
virtual jsk_recognition_utils::Cube::Ptr cubeFromIndicesAndCoefficients(const pcl::PointCloud< PointT >::Ptr cloud, const IndicesCoefficientsTriple &indices_coefficients_triple, pcl::PointCloud< EdgebasedCubeFinder::PointT >::Ptr points_on_edge)
Definition: edgebased_cube_finder_nodelet.cpp:639
p
p
jsk_pcl_ros::CubeHypothesis::computeAxisEndPoints
virtual jsk_recognition_utils::PointPair computeAxisEndPoints(const jsk_recognition_utils::Line &axis, const jsk_recognition_utils::PointPair &a_candidates, const jsk_recognition_utils::PointPair &b_candidates)
Definition: edgebased_cube_finder_nodelet.cpp:180
M_PI
#define M_PI
jsk_pcl_ros::EdgebasedCubeFinder::countInliers
virtual int countInliers(const pcl::PointCloud< PointT >::Ptr cloud, const jsk_recognition_utils::ConvexPolygon::Ptr convex)
Definition: edgebased_cube_finder_nodelet.cpp:365
jsk_pcl_ros::EdgebasedCubeFinder::filterPairsBasedOnParallelEdgeDistances
virtual void filterPairsBasedOnParallelEdgeDistances(const std::vector< IndicesPair > &pairs, const std::vector< CoefficientsPair > &coefficients_pair, std::vector< IndicesPair > &filtered_indices_pairs, std::vector< CoefficientsPair > &filtered_coefficients_pairs)
Definition: edgebased_cube_finder_nodelet.cpp:536
PCLIndicesMsg
pcl::PointIndices PCLIndicesMsg
jsk_pcl_ros::IndicesPair
boost::tuple< pcl::PointIndices::Ptr, pcl::PointIndices::Ptr > IndicesPair
Definition: edgebased_cube_finder.h:100
jsk_pcl_ros::EdgebasedCubeFinder::sub_edges_
message_filters::Subscriber< jsk_recognition_msgs::ParallelEdgeArray > sub_edges_
Definition: edgebased_cube_finder.h:320
pcl_conversions::toPCL
void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
cube
Cube cube(Eigen::Vector3f(1, 0, 0), Eigen::Quaternionf(0.108755, 0.088921, 0.108755, 0.984092), Eigen::Vector3f(0.3, 0.3, 0.3))
jsk_pcl_ros::EdgebasedCubeFinder::min_inliers_
double min_inliers_
Definition: edgebased_cube_finder.h:330
theta
int theta
NODELET_WARN
#define NODELET_WARN(...)
jsk_pcl_ros::CubeHypothesis::~CubeHypothesis
virtual ~CubeHypothesis()
Definition: edgebased_cube_finder_nodelet.cpp:98
jsk_pcl_ros::CubeHypothesis::CubeHypothesis
CubeHypothesis(const IndicesPair &pair, const CoefficientsPair &coefficients_pair, const double outlier_threshold)
Definition: edgebased_cube_finder_nodelet.cpp:89
jsk_pcl_ros::EdgebasedCubeFinder::combinateCoefficients
virtual std::vector< CoefficientsPair > combinateCoefficients(const std::vector< pcl::ModelCoefficients::Ptr > &coefficients)
Definition: edgebased_cube_finder_nodelet.cpp:1257
pcl_conversions::convertToPCLPointIndices
std::vector< pcl::PointIndices::Ptr > convertToPCLPointIndices(const std::vector< PCLIndicesMsg > &cluster_indices)
jsk_pcl_ros::EdgebasedCubeFinder::filterBasedOnConvex
virtual void filterBasedOnConvex(const pcl::PointCloud< PointT >::Ptr cloud, const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes, std::vector< int > &output_indices)
Definition: edgebased_cube_finder_nodelet.cpp:382
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
jsk_pcl_ros::CubeHypothesis::outlier_threshold_
double outlier_threshold_
Definition: edgebased_cube_finder.h:155
jsk_pcl_ros::EdgebasedCubeFinder::B_PERPENDICULAR
@ B_PERPENDICULAR
Definition: edgebased_cube_finder.h:201
jsk_recognition_utils::rotFrom3Axis
Eigen::Quaternionf rotFrom3Axis(const Eigen::Vector3f &ex, const Eigen::Vector3f &ey, const Eigen::Vector3f &ez)
edgebased_cube_finder.h
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
jsk_pcl_ros::CubeHypothesis::computeCentroid
virtual void computeCentroid(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointIndices::Ptr &indices, Eigen::Vector3f &output)
Definition: edgebased_cube_finder_nodelet.cpp:102
message_filters::Subscriber::unsubscribe
void unsubscribe()
cloud
cloud
jsk_pcl_ros::EdgebasedCubeFinder::isPerpendicularVector
virtual bool isPerpendicularVector(const Eigen::Vector3f &a, const Eigen::Vector3f &b)
Definition: edgebased_cube_finder_nodelet.cpp:812
jsk_pcl_ros::EdgebasedCubeFinder::C_PERPENDICULAR
@ C_PERPENDICULAR
Definition: edgebased_cube_finder.h:202
jsk_pcl_ros::EdgebasedCubeFinder::NOT_PERPENDICULAR
@ NOT_PERPENDICULAR
Definition: edgebased_cube_finder.h:199
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::EdgebasedCubeFinder, nodelet::Nodelet)
jsk_pcl_ros::EdgebasedCubeFinder::outlier_threshold_
double outlier_threshold_
Definition: edgebased_cube_finder.h:329
class_list_macros.h
jsk_recognition_utils::ConvexPolygon::distanceSmallerThan
bool distanceSmallerThan(const Eigen::Vector3f &p, double distance_threshold)
jsk_pcl_ros::EdgebasedCubeFinder::perpendicularEdgeTriple
virtual EdgeRelation perpendicularEdgeTriple(const jsk_recognition_utils::Line &edge_a, const jsk_recognition_utils::Line &edge_b, const jsk_recognition_utils::Line &edge_c)
Definition: edgebased_cube_finder_nodelet.cpp:832
jsk_recognition_utils::Line::fromCoefficients
static Ptr fromCoefficients(const std::vector< float > &coefficients)
jsk_pcl_ros::EdgebasedCubeFinder::estimate
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr &input_edges)
Definition: edgebased_cube_finder_nodelet.cpp:750
jsk_pcl_ros::DiagnoalCubeHypothesis::estimate
virtual void estimate(const pcl::PointCloud< pcl::PointXYZRGB > &cloud)
Definition: edgebased_cube_finder_nodelet.cpp:237
jsk_pcl_ros::EdgebasedCubeFinder::parallel_edge_distance_max_threshold_
double parallel_edge_distance_max_threshold_
Definition: edgebased_cube_finder.h:333
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::EdgebasedCubeFinder::subscribe
virtual void subscribe()
Definition: edgebased_cube_finder_nodelet.cpp:454
jsk_pcl_ros::EdgebasedCubeFinder::parallel_edge_distance_min_threshold_
double parallel_edge_distance_min_threshold_
Definition: edgebased_cube_finder.h:333
jsk_pcl_ros::EdgebasedCubeFinder::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: edgebased_cube_finder.h:319
k
int k
jsk_recognition_utils::Line::parallelLineNormal
virtual void parallelLineNormal(const Line &other, Eigen::Vector3f &output) const
jsk_pcl_ros::CubeHypothesis::getLinePoints
virtual void getLinePoints(const jsk_recognition_utils::Line &line, const pcl::PointCloud< pcl::PointXYZRGB > &cloud, const pcl::PointIndices::Ptr indices, jsk_recognition_utils::Vertices &output)
Definition: edgebased_cube_finder_nodelet.cpp:118
PointT
pcl::PointXYZRGB PointT
eigen_msg.h
jsk_pcl_ros::EdgebasedCubeFinder::midLineFromCoefficientsPair
virtual jsk_recognition_utils::Line::Ptr midLineFromCoefficientsPair(const CoefficientsPair &pair)
Definition: edgebased_cube_finder_nodelet.cpp:473
jsk_recognition_utils::Line::foot
virtual void foot(const Eigen::Vector3f &point, Eigen::Vector3f &output) const
attention_pose_set.r
r
Definition: attention_pose_set.py:9
_1
boost::arg< 1 > _1
jsk_pcl_ros::EdgebasedCubeFinder::pub_pose_array_
ros::Publisher pub_pose_array_
Definition: edgebased_cube_finder.h:322
alpha
alpha
jsk_pcl_ros::EdgebasedCubeFinder::onInit
virtual void onInit()
Definition: edgebased_cube_finder_nodelet.cpp:414
jsk_pcl_ros::CubeHypothesis::coefficients_pair_
const CoefficientsPair coefficients_pair_
Definition: edgebased_cube_finder.h:154
sample_simulate_tabletop_cloud.points
def points
Definition: sample_simulate_tabletop_cloud.py:161
pcl_conversion_util.h
line
jsk_recognition_utils::Line::computeAlpha
virtual double computeAlpha(const Point &p) const
distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
jsk_pcl_ros::EdgebasedCubeFinder::filterPerpendicularEdgeTriples
virtual std::vector< IndicesCoefficientsTriple > filterPerpendicularEdgeTriples(const std::vector< IndicesCoefficientsTriple > &triples)
Definition: edgebased_cube_finder_nodelet.cpp:865
jsk_pcl_ros::IndicesCoefficientsTriple
boost::tuple< IndicesTriple, CoefficientsTriple > IndicesCoefficientsTriple
Definition: edgebased_cube_finder.h:109
jsk_pcl_ros::EdgebasedCubeFinder::PointT
pcl::PointXYZRGB PointT
Definition: edgebased_cube_finder.h:195
num
num
message_filters::Subscriber::subscribe
void subscribe()
jsk_pcl_ros::EdgebasedCubeFinder::estimateConvexPolygon
virtual jsk_recognition_utils::ConvexPolygon::Ptr estimateConvexPolygon(const pcl::PointCloud< PointT >::Ptr cloud, const pcl::PointIndices::Ptr indices, pcl::ModelCoefficients::Ptr coefficients, pcl::PointIndices::Ptr inliers)
Definition: edgebased_cube_finder_nodelet.cpp:1214
NODELET_INFO
#define NODELET_INFO(...)
dot
T dot(T *pf1, T *pf2, int length)
jsk_pcl_ros::EdgebasedCubeFinder::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: edgebased_cube_finder_nodelet.cpp:403
jsk_recognition_utils::addIndices
pcl::PointIndices::Ptr addIndices(const pcl::PointIndices &a, const pcl::PointIndices &b)
nodelet::Nodelet
jsk_pcl_ros::EdgebasedCubeFinder::tripleIndicesAndCoefficients
virtual std::vector< IndicesCoefficientsTriple > tripleIndicesAndCoefficients(const std::vector< pcl::PointIndices::Ptr > &indices, const std::vector< pcl::ModelCoefficients::Ptr > &coefficients)
Definition: edgebased_cube_finder_nodelet.cpp:1179
jsk_pcl_ros::EdgebasedCubeFinder::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: edgebased_cube_finder.h:317
jsk_pcl_ros::EdgebasedCubeFinder::convexFromPairs
virtual jsk_recognition_utils::ConvexPolygon::Ptr convexFromPairs(const pcl::PointCloud< PointT >::Ptr cloud, const CoefficientsPair &coefficients_pair, const IndicesPair &indices_pair)
Definition: edgebased_cube_finder_nodelet.cpp:510
jsk_pcl_ros::EdgebasedCubeFinder::preparePointCloudForRANSAC
virtual pcl::PointIndices::Ptr preparePointCloudForRANSAC(const jsk_recognition_utils::ConvexPolygon::Ptr convex, const CoefficientsPair &edge_coefficients_pair, const pcl::PointCloud< PointT >::Ptr cloud)
Definition: edgebased_cube_finder_nodelet.cpp:571
jsk_pcl_ros::EdgebasedCubeFinder::unsubscribe
virtual void unsubscribe()
Definition: edgebased_cube_finder_nodelet.cpp:467
jsk_pcl_ros::EdgebasedCubeFinder::convex_area_threshold_
double convex_area_threshold_
Definition: edgebased_cube_finder.h:331
jsk_pcl_ros::EdgebasedCubeFinder::A_PERPENDICULAR
@ A_PERPENDICULAR
Definition: edgebased_cube_finder.h:200
dump_depth_error.f
f
Definition: dump_depth_error.py:39
jsk_pcl_ros::EdgebasedCubeFinder::~EdgebasedCubeFinder
virtual ~EdgebasedCubeFinder()
Definition: edgebased_cube_finder_nodelet.cpp:443
jsk_pcl_ros::EdgebasedCubeFinder::combinateIndices
virtual std::vector< IndicesPair > combinateIndices(const std::vector< pcl::PointIndices::Ptr > &indices)
Definition: edgebased_cube_finder_nodelet.cpp:1243
jsk_pcl_ros::EdgebasedCubeFinder
Definition: edgebased_cube_finder.h:189
jsk_pcl_ros::EdgebasedCubeFinder::pub_
ros::Publisher pub_
Definition: edgebased_cube_finder.h:321
coefficients
coefficients
jsk_pcl_ros::PlanarCubeHypothesis::PlanarCubeHypothesis
PlanarCubeHypothesis(const IndicesPair &pair, const CoefficientsPair &coefficients_pair, const double outlier_threshold)
Definition: edgebased_cube_finder_nodelet.cpp:222
index
unsigned int index
jsk_pcl_ros::EdgebasedCubeFinder::extractPointCloud
virtual pcl::PointCloud< PointT >::Ptr extractPointCloud(const pcl::PointCloud< PointT >::Ptr cloud, const pcl::PointIndices::Ptr indices)
Definition: edgebased_cube_finder_nodelet.cpp:483
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
jsk_pcl_ros::EdgebasedCubeFinder::mutex_
boost::mutex mutex_
Definition: edgebased_cube_finder.h:325
jsk_recognition_utils::Cube
jsk_recognition_utils::Line
jsk_pcl_ros::CubeHypothesis::indices_pair_
const IndicesPair indices_pair_
Definition: edgebased_cube_finder.h:153
jsk_pcl_ros::EdgebasedCubeFinder::EdgeRelation
EdgeRelation
Definition: edgebased_cube_finder.h:197
jsk_pcl_ros::CoefficientsTriple
boost::tuple< pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr > CoefficientsTriple
Definition: edgebased_cube_finder.h:107
ROS_INFO
#define ROS_INFO(...)
jsk_pcl_ros::DiagnoalCubeHypothesis::DiagnoalCubeHypothesis
DiagnoalCubeHypothesis(const IndicesPair &pair, const CoefficientsPair &coefficients_pair, const double outlier_threshold)
Definition: edgebased_cube_finder_nodelet.cpp:229
jsk_recognition_utils::PointPair
boost::tuple< Point, Point > PointPair
a
char a[26]
config
config
jsk_pcl_ros::EdgebasedCubeFinder::estimateParallelPlane
virtual void estimateParallelPlane(const jsk_recognition_utils::ConvexPolygon::Ptr convex, const pcl::PointCloud< PointT >::Ptr filtered_cloud, pcl::PointIndices::Ptr output_inliers, pcl::ModelCoefficients::Ptr output_coefficients)
Definition: edgebased_cube_finder_nodelet.cpp:596
jsk_pcl_ros::CubeHypothesis::cube_
jsk_recognition_utils::Cube::Ptr cube_
Definition: edgebased_cube_finder.h:156
jsk_pcl_ros::EdgebasedCubeFinder::pub_debug_clusers_
ros::Publisher pub_debug_clusers_
Definition: edgebased_cube_finder.h:324
jsk_pcl_ros::EdgebasedCubeFinder::estimatePerpendicularPlane
virtual void estimatePerpendicularPlane(const jsk_recognition_utils::ConvexPolygon::Ptr convex, const CoefficientsPair &edge_coefficients, const pcl::PointCloud< PointT >::Ptr filtered_cloud, pcl::PointIndices::Ptr output_inliers, pcl::ModelCoefficients::Ptr output_coefficients)
Definition: edgebased_cube_finder_nodelet.cpp:615
v
GLfloat v[8][3]
jsk_recognition_utils::ConvexPolygon::Ptr
boost::shared_ptr< ConvexPolygon > Ptr
jsk_pcl_ros::EdgebasedCubeFinder::pub_debug_filtered_cloud_
ros::Publisher pub_debug_filtered_cloud_
Definition: edgebased_cube_finder.h:323
jsk_pcl_ros::IndicesTriple
boost::tuple< pcl::PointIndices::Ptr, pcl::PointIndices::Ptr, pcl::PointIndices::Ptr > IndicesTriple
Definition: edgebased_cube_finder.h:105
jsk_pcl_ros::EdgebasedCubeFinder::estimate2
virtual void estimate2(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr &input_edges)
Definition: edgebased_cube_finder_nodelet.cpp:920
jsk_recognition_utils::Vertices
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
jsk_pcl_ros::EdgebasedCubeFinder::pub_debug_marker_
ros::Publisher pub_debug_marker_
Definition: edgebased_cube_finder.h:323
jsk_pcl_ros::DiagnoalCubeHypothesis::min_angle_
double min_angle_
Definition: edgebased_cube_finder.h:185
pcl_conversions.h


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