00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00033 #include <door_handle_detector/geometric_helper.h>
00034
00035 using namespace std;
00036
00038
00048 void
00049 obtainCloudIndicesSet (const sensor_msgs::PointCloud &points, vector<int> &indices, door_msgs::Door& door,
00050 tf::TransformListener *tf, std::string parameter_frame,
00051 double min_z_bounds, double max_z_bounds, double frame_multiplier)
00052 {
00053
00054 string cloud_frame = points.header.frame_id;
00055 string door_frame = door.header.frame_id;
00056
00057
00058 indices.resize (points.points.size ());
00059
00060
00061 tf::Stamped<geometry_msgs::Point32> frame_p1 (door.frame_p1, points.header.stamp, door_frame);
00062 tf::Stamped<geometry_msgs::Point32> frame_p2 (door.frame_p2, points.header.stamp, door_frame);
00063 transformPoint (tf, cloud_frame, frame_p1, frame_p1);
00064 transformPoint (tf, cloud_frame, frame_p2, frame_p2);
00065
00066 ROS_INFO ("Start detecting door at points in frame %s [%g, %g, %g] -> [%g, %g, %g]",
00067 cloud_frame.c_str (), frame_p1.x, frame_p1.y, frame_p1.z, frame_p2.x, frame_p2.y, frame_p2.z);
00068
00069
00070 geometry_msgs::Point32 min_bbox, max_bbox;
00071
00072 if (frame_multiplier == -1)
00073 {
00074 ROS_INFO ("Door frame multiplier set to -1. Using the entire point cloud data.");
00075
00076 cloud_geometry::statistics::getMinMax (points, min_bbox, max_bbox);
00077 for (unsigned int i = 0; i < points.points.size (); i++)
00078 indices[i] = i;
00079 }
00080 else
00081 {
00082
00083 min_z_bounds = transformDoubleValueTF (min_z_bounds, parameter_frame, cloud_frame, points.header.stamp, tf);
00084 max_z_bounds = transformDoubleValueTF (max_z_bounds, parameter_frame, cloud_frame, points.header.stamp, tf);
00085 ROS_INFO ("Capping Z-search using the door_min_z_bounds/door_max_z_bounds parameters in frame %s: [%g / %g]",
00086 cloud_frame.c_str (), min_z_bounds, max_z_bounds);
00087
00088
00089 get3DBounds (&frame_p1, &frame_p2, min_bbox, max_bbox, min_z_bounds, max_z_bounds, frame_multiplier);
00090
00091 int nr_p = 0;
00092 for (unsigned int i = 0; i < points.points.size (); i++)
00093 {
00094 if ((points.points[i].x >= min_bbox.x && points.points[i].x <= max_bbox.x) &&
00095 (points.points[i].y >= min_bbox.y && points.points[i].y <= max_bbox.y) &&
00096 (points.points[i].z >= min_bbox.z && points.points[i].z <= max_bbox.z))
00097 {
00098 indices[nr_p] = i;
00099 nr_p++;
00100 }
00101 }
00102 indices.resize (nr_p);
00103 }
00104
00105
00106 ROS_INFO ("Number of points in bounds [%f,%f,%f] -> [%f,%f,%f]: %d.",
00107 min_bbox.x, min_bbox.y, min_bbox.z, max_bbox.x, max_bbox.y, max_bbox.z, (int)indices.size ());
00108 }
00109
00111 bool
00112 checkDoorEdges (const geometry_msgs::Polygon &poly, const geometry_msgs::Point32 &z_axis, double min_height, double eps_angle,
00113 double &door_frame1, double &door_frame2)
00114 {
00115
00116 geometry_msgs::Point32 centroid;
00117 cloud_geometry::nearest::computeCentroid (poly, centroid);
00118
00119
00120 std::vector<int> inliers_left, inliers_right;
00121 for (unsigned int i = 0; i < poly.points.size (); i++)
00122 {
00123 if (poly.points[i].x < centroid.x)
00124 {
00125 if (poly.points[i].y < centroid.y)
00126 inliers_left.push_back (i);
00127 else
00128 inliers_right.push_back (i);
00129 }
00130 else
00131 {
00132 if (poly.points[i].y < centroid.y)
00133 inliers_left.push_back (i);
00134 else
00135 inliers_right.push_back (i);
00136 }
00137 }
00138
00139 door_frame1 = door_frame2 = 0.0;
00140 geometry_msgs::Point32 line_dir;
00141
00142 std::vector<geometry_msgs::Point32> new_points;
00143 for (unsigned int i = 0; i < inliers_left.size () - 1; i++)
00144 {
00145
00146 if (cloud_geometry::checkPointEqual (poly.points.at (inliers_left[i]), poly.points.at (inliers_left[i+1])))
00147 continue;
00148
00149 if (fabs (inliers_left[i] - inliers_left[i+1]) > 1)
00150 continue;
00151
00152
00153 line_dir.x = poly.points.at (inliers_left[i]).x - poly.points.at (inliers_left[i+1]).x;
00154 line_dir.y = poly.points.at (inliers_left[i]).y - poly.points.at (inliers_left[i+1]).y;
00155 line_dir.z = poly.points.at (inliers_left[i]).z - poly.points.at (inliers_left[i+1]).z;
00156
00157
00158 double angle = cloud_geometry::angles::getAngle3D (line_dir, z_axis);
00159 if ( (angle < eps_angle) || ( (M_PI - angle) < eps_angle ) )
00160 {
00161
00162 double line_length = cloud_geometry::distances::pointToPointDistance (poly.points.at (inliers_left[i]), poly.points.at (inliers_left[i+1]));
00163 door_frame1 += line_length;
00164
00165 new_points.push_back (poly.points.at (inliers_left[i]));
00166 new_points.push_back (poly.points.at (inliers_left[i+1]));
00167 }
00168 }
00169
00170
00171 for (unsigned int i = 0; i < inliers_right.size () - 1; i++)
00172 {
00173
00174 if (cloud_geometry::checkPointEqual (poly.points.at (inliers_right[i]), poly.points.at (inliers_right[i+1])))
00175 continue;
00176
00177 if (fabs (inliers_right[i] - inliers_right[i+1]) > 1)
00178 continue;
00179
00180 line_dir.x = poly.points.at (inliers_right[i]).x - poly.points.at (inliers_right[i+1]).x;
00181 line_dir.y = poly.points.at (inliers_right[i]).y - poly.points.at (inliers_right[i+1]).y;
00182 line_dir.z = poly.points.at (inliers_right[i]).z - poly.points.at (inliers_right[i+1]).z;
00183
00184
00185 double angle = cloud_geometry::angles::getAngle3D (line_dir, z_axis);
00186 if ( (angle < eps_angle) || ( (M_PI - angle) < eps_angle ) )
00187 {
00188
00189 double line_length = cloud_geometry::distances::pointToPointDistance (poly.points.at (inliers_right[i]), poly.points.at (inliers_right[i+1]));
00190 door_frame2 += line_length;
00191
00192 new_points.push_back (poly.points.at (inliers_right[i]));
00193 new_points.push_back (poly.points.at (inliers_right[i+1]));
00194 }
00195 }
00196
00197 if (door_frame1 < min_height || door_frame2 < min_height || fabs (door_frame2 - door_frame1) > 2 * min (door_frame1, door_frame2))
00198 return (false);
00199 return (true);
00200 }
00201
00203
00212 void
00213 get3DBounds (geometry_msgs::Point32 *p1, geometry_msgs::Point32 *p2, geometry_msgs::Point32 &min_b, geometry_msgs::Point32 &max_b,
00214 double min_z_bounds, double max_z_bounds, int multiplier)
00215 {
00216
00217 float door_frame = sqrt ( (p1->x - p2->x) * (p1->x - p2->x) + (p1->y - p2->y) * (p1->y - p2->y) );
00218
00219 float center[2];
00220 center[0] = (p1->x + p2->x) / 2.0;
00221 center[1] = (p1->y + p2->y) / 2.0;
00222
00223
00224 min_b.x = center[0] + (multiplier * door_frame) / 2.0;
00225 min_b.y = center[1] + (multiplier * door_frame) / 2.0;
00226 min_b.z = min_z_bounds;
00227
00228 max_b.x = center[0] - (multiplier * door_frame) / 2.0;
00229 max_b.y = center[1] - (multiplier * door_frame) / 2.0;
00230 max_b.z = max_z_bounds;
00231
00232
00233 if (min_b.x > max_b.x)
00234 {
00235 float tmp = min_b.x;
00236 min_b.x = max_b.x;
00237 max_b.x = tmp;
00238 }
00239 if (min_b.y > max_b.y)
00240 {
00241 float tmp = min_b.y;
00242 min_b.y = max_b.y;
00243 max_b.y = tmp;
00244 }
00245 }
00246
00248
00253 void
00254 getCloudViewPoint (const string cloud_frame, geometry_msgs::PointStamped &viewpoint_cloud, const tf::TransformListener *tf)
00255 {
00256
00257 geometry_msgs::PointStamped viewpoint_laser;
00258 viewpoint_laser.header.frame_id = "laser_tilt_mount_link";
00259
00260 viewpoint_laser.point.x = viewpoint_laser.point.y = viewpoint_laser.point.z = 0.0;
00261
00262 try
00263 {
00264 tf->transformPoint (cloud_frame, viewpoint_laser, viewpoint_cloud);
00265 ROS_INFO ("Cloud view point in frame %s is: %g, %g, %g.", cloud_frame.c_str (),
00266 viewpoint_cloud.point.x, viewpoint_cloud.point.y, viewpoint_cloud.point.z);
00267 }
00268 catch (tf::ConnectivityException)
00269 {
00270 ROS_WARN ("Could not transform a point from frame %s to frame %s!", viewpoint_laser.header.frame_id.c_str (), cloud_frame.c_str ());
00271
00272 viewpoint_cloud.point.x = 0.05; viewpoint_cloud.point.y = 0.0; viewpoint_cloud.point.z = 0.942768;
00273 }
00274 }
00275
00277
00284 void
00285 selectBestDistributionStatistics (const sensor_msgs::PointCloud &points, const vector<int> &indices, int d_idx, vector<int> &inliers)
00286 {
00287 double mean, stddev;
00288
00289 cloud_geometry::statistics::getChannelMeanStd (points, indices, d_idx, mean, stddev);
00290
00291
00292
00293 vector<int> alpha_vals (71);
00294 int nr_a = 0;
00295 for (double alpha = 0; alpha < 7; alpha += .1)
00296 {
00297 cloud_geometry::statistics::selectPointsOutsideDistribution (points, indices, d_idx, mean, stddev, alpha,
00298 inliers);
00299 alpha_vals[nr_a] = inliers.size ();
00300
00301 nr_a++;
00302 }
00303 alpha_vals.resize (nr_a);
00304
00305
00306 double trimean;
00307 cloud_geometry::statistics::getTrimean (alpha_vals, trimean);
00308
00309
00310
00311 int best_i = 0;
00312 double best_alpha = DBL_MAX;
00313 for (unsigned int i = 0; i < alpha_vals.size (); i++)
00314 {
00315 double c_val = fabs ((double)alpha_vals[i] - trimean);
00316 if (c_val < best_alpha)
00317 {
00318 best_alpha = c_val;
00319 best_i = i;
00320 }
00321 }
00322
00323 best_alpha = best_i / 10.0;
00324
00325
00326
00327 cloud_geometry::statistics::selectPointsOutsideDistribution (points, indices, d_idx, mean, stddev, best_alpha, inliers);
00328 }
00329
00331
00339 void
00340 selectBestDualDistributionStatistics (const sensor_msgs::PointCloud &points, const vector<int> &indices, int d_idx_1, int d_idx_2,
00341 vector<int> &inliers)
00342 {
00343 vector<int> inliers_1, inliers_2;
00344 double mean_1, stddev_1, mean_2, stddev_2;
00345
00346 cloud_geometry::statistics::getChannelMeanStd (points, indices, d_idx_1, mean_1, stddev_1);
00347
00348 cloud_geometry::statistics::getChannelMeanStd (points, indices, d_idx_2, mean_2, stddev_2);
00349
00350
00351
00352
00353
00354 vector<int> alpha_vals_1 (71), alpha_vals_2 (71);
00355 int nr_a = 0;
00356 for (double alpha = 0; alpha < 7; alpha += .1)
00357 {
00358 cloud_geometry::statistics::selectPointsOutsideDistribution (points, indices, d_idx_1, mean_1, stddev_1, alpha,
00359 inliers_1);
00360 cloud_geometry::statistics::selectPointsOutsideDistribution (points, indices, d_idx_2, mean_2, stddev_2, alpha,
00361 inliers_2);
00362 alpha_vals_1[nr_a] = inliers_1.size ();
00363 alpha_vals_2[nr_a] = inliers_2.size ();
00364 nr_a++;
00365 }
00366 alpha_vals_1.resize (nr_a);
00367 alpha_vals_2.resize (nr_a);
00368
00369
00370
00371
00372
00373
00374 double trimean_1, trimean_2;
00375 cloud_geometry::statistics::getTrimean (alpha_vals_1, trimean_1);
00376 cloud_geometry::statistics::getTrimean (alpha_vals_2, trimean_2);
00377
00378
00379 int best_i_1 = 0, best_i_2 = 0;
00380 double best_alpha_1 = DBL_MAX, best_alpha_2 = DBL_MAX;
00381 for (unsigned int i = 0; i < alpha_vals_1.size (); i++)
00382 {
00383 double c_val_1 = fabs ((double)alpha_vals_1[i] - trimean_1);
00384 if (c_val_1 < best_alpha_1)
00385 {
00386 best_alpha_1 = c_val_1;
00387 best_i_1 = i;
00388 }
00389 double c_val_2 = fabs ((double)alpha_vals_2[i] - trimean_2);
00390 if (c_val_2 < best_alpha_2)
00391 {
00392 best_alpha_2 = c_val_2;
00393 best_i_2 = 2;
00394 }
00395 }
00396
00397 best_alpha_1 = best_i_1 / 10.0;
00398 best_alpha_2 = best_i_2 / 10.0;
00399
00400
00401
00402 cloud_geometry::statistics::selectPointsOutsideDistribution (points, indices, d_idx_1, mean_1, stddev_1, best_alpha_1, inliers_1);
00403 cloud_geometry::statistics::selectPointsOutsideDistribution (points, indices, d_idx_2, mean_2, stddev_2, best_alpha_2, inliers_2);
00404
00405
00406 sort (inliers_1.begin (), inliers_1.end ());
00407 sort (inliers_2.begin (), inliers_2.end ());
00408 set_intersection (inliers_1.begin (), inliers_1.end (), inliers_2.begin (), inliers_2.end (), inserter (inliers, inliers.begin ()));
00409 }
00410
00412
00419 bool
00420 checkIfClusterPerpendicular (const sensor_msgs::PointCloud &points, const vector<int> &indices, geometry_msgs::PointStamped *viewpoint,
00421 vector<double> *coeff, double eps_angle)
00422 {
00423
00424 geometry_msgs::Point32 centroid;
00425 cloud_geometry::nearest::computeCentroid (points, indices, centroid);
00426
00427
00428 centroid.x -= viewpoint->point.x;
00429 centroid.y -= viewpoint->point.y;
00430 centroid.z -= viewpoint->point.z;
00431
00432
00433 Eigen::Vector4d plane_parameters;
00434 double curvature;
00435 cloud_geometry::nearest::computePointNormal (points, indices, plane_parameters, curvature);
00436 geometry_msgs::Point32 normal;
00437 normal.x = plane_parameters (0);
00438 normal.y = plane_parameters (1);
00439 normal.z = plane_parameters (2);
00440
00441
00442
00443
00444
00445 double angle = cloud_geometry::angles::getAngle3D (centroid, normal);
00446 if ( (angle < eps_angle) || ( (M_PI - angle) < eps_angle ) )
00447 return (true);
00448 return (false);
00449 }
00450
00452
00465 void
00466 findClusters (const sensor_msgs::PointCloud &points, const vector<int> &indices, double tolerance, vector<vector<int> > &clusters,
00467 int nx_idx, int ny_idx, int nz_idx,
00468 double eps_angle, unsigned int min_pts_per_cluster)
00469 {
00470
00471 cloud_kdtree::KdTree* tree = new cloud_kdtree::KdTreeANN (points, indices);
00472
00473 int nr_points = indices.size ();
00474
00475 vector<bool> processed;
00476 processed.resize (nr_points, false);
00477
00478 vector<int> nn_indices;
00479 vector<float> nn_distances;
00480
00481 for (int i = 0; i < nr_points; i++)
00482 {
00483 if (processed[i])
00484 continue;
00485
00486 vector<int> seed_queue;
00487 int sq_idx = 0;
00488 seed_queue.push_back (i);
00489
00490
00491
00492
00493
00494
00495
00496 processed[i] = true;
00497
00498 while (sq_idx < (int)seed_queue.size ())
00499 {
00500
00501 tree->radiusSearch (seed_queue.at (sq_idx), tolerance, nn_indices, nn_distances);
00502
00503 for (unsigned int j = 1; j < nn_indices.size (); j++)
00504 {
00505 if (processed.at (nn_indices[j]))
00506 continue;
00507
00508 processed[nn_indices[j]] = true;
00509 if (nx_idx != -1)
00510 {
00511
00512
00513
00514
00515 double dot_p = points.channels[nx_idx].values[indices.at (i)] * points.channels[nx_idx].values[indices.at (nn_indices[j])] +
00516 points.channels[ny_idx].values[indices.at (i)] * points.channels[ny_idx].values[indices.at (nn_indices[j])] +
00517 points.channels[nz_idx].values[indices.at (i)] * points.channels[nz_idx].values[indices.at (nn_indices[j])];
00518
00519 if ( fabs (acos (dot_p)) < eps_angle )
00520 {
00521 processed[nn_indices[j]] = true;
00522 seed_queue.push_back (nn_indices[j]);
00523 }
00524 }
00525
00526 else
00527 {
00528 processed[nn_indices[j]] = true;
00529 seed_queue.push_back (nn_indices[j]);
00530 }
00531 }
00532
00533 sq_idx++;
00534 }
00535
00536
00537 if (seed_queue.size () >= min_pts_per_cluster)
00538 {
00539 vector<int> r (seed_queue.size ());
00540 for (unsigned int j = 0; j < seed_queue.size (); j++)
00541 r[j] = indices.at (seed_queue[j]);
00542
00543 sort (r.begin (), r.end ());
00544 r.erase (unique (r.begin (), r.end ()), r.end ());
00545
00546 clusters.push_back (r);
00547 }
00548 }
00549
00550
00551 delete tree;
00552 }
00553
00555
00564 bool
00565 fitSACPlane (sensor_msgs::PointCloud &points, vector<int> indices, vector<int> &inliers, vector<double> &coeff,
00566 const geometry_msgs::PointStamped &viewpoint_cloud, double dist_thresh, int min_pts)
00567 {
00568 if ((int)indices.size () < min_pts)
00569 {
00570 inliers.resize (0);
00571 coeff.resize (0);
00572 return (false);
00573 }
00574
00575
00576 sample_consensus::SACModelPlane *model = new sample_consensus::SACModelPlane ();
00577 sample_consensus::SAC *sac = new sample_consensus::RANSAC (model, dist_thresh);
00578
00579 sac->setMaxIterations (500);
00580 model->setDataSet (&points, indices);
00581
00582
00583 if (sac->computeModel ())
00584 {
00585
00586 if ((int)sac->getInliers ().size () < min_pts)
00587 {
00588
00589 inliers.resize (0);
00590 coeff.resize (0);
00591 return (false);
00592 }
00593 sac->computeCoefficients (coeff);
00594 sac->refineCoefficients (coeff);
00595 model->selectWithinDistance (coeff, dist_thresh, inliers);
00596
00597
00598 cloud_geometry::angles::flipNormalTowardsViewpoint (coeff, points.points.at (inliers[0]), viewpoint_cloud);
00599
00600
00601
00602
00603
00604 model->projectPointsInPlace (inliers, coeff);
00605 }
00606 else
00607 {
00608 ROS_ERROR ("Could not compute a plane model.");
00609 return (false);
00610 }
00611 sort (inliers.begin (), inliers.end ());
00612
00613 delete sac;
00614 delete model;
00615 return (true);
00616 }
00617
00619
00626 void
00627 estimatePointNormals (const sensor_msgs::PointCloud &points, const vector<int> &point_indices, sensor_msgs::PointCloud &points_down, int k, const geometry_msgs::PointStamped &viewpoint_cloud)
00628 {
00629
00630 points_down.channels.resize (4);
00631 points_down.channels[0].name = "nx";
00632 points_down.channels[1].name = "ny";
00633 points_down.channels[2].name = "nz";
00634 points_down.channels[3].name = "curvatures";
00635 for (unsigned int d = 0; d < points_down.channels.size (); d++)
00636 points_down.channels[d].values.resize (points_down.points.size ());
00637
00638
00639 cloud_kdtree::KdTree *kdtree = new cloud_kdtree::KdTreeANN (points, point_indices);
00640
00641
00642 vector<vector<int> > points_k_indices (points_down.points.size ());
00643 vector<float> distances;
00644
00645
00646 for (int i = 0; i < (int)points_down.points.size (); i++)
00647 {
00648
00649 kdtree->radiusSearch (points_down.points[i], 0.025, points_k_indices[i], distances);
00650 }
00651
00652 #pragma omp parallel for schedule(dynamic)
00653 for (int i = 0; i < (int)points_down.points.size (); i++)
00654 {
00655
00656 Eigen::Vector4d plane_parameters;
00657 double curvature;
00658 for (int j = 0; j < (int)points_k_indices[i].size (); j++)
00659 points_k_indices[i][j] = point_indices.at (points_k_indices[i][j]);
00660 cloud_geometry::nearest::computePointNormal (points, points_k_indices[i], plane_parameters, curvature);
00661
00662 cloud_geometry::angles::flipNormalTowardsViewpoint (plane_parameters, points_down.points[i], viewpoint_cloud);
00663
00664 points_down.channels[0].values[i] = plane_parameters (0);
00665 points_down.channels[1].values[i] = plane_parameters (1);
00666 points_down.channels[2].values[i] = plane_parameters (2);
00667 points_down.channels[3].values[i] = curvature;
00668 }
00669
00670 delete kdtree;
00671 }
00672
00674
00680 void
00681 estimatePointNormals (sensor_msgs::PointCloud &points, const vector<int> &point_indices, int k, const geometry_msgs::PointStamped &viewpoint_cloud)
00682 {
00683 int old_channel_size = points.channels.size ();
00684
00685 points.channels.resize (old_channel_size + 4);
00686 points.channels[old_channel_size + 0].name = "nx";
00687 points.channels[old_channel_size + 1].name = "ny";
00688 points.channels[old_channel_size + 2].name = "nz";
00689 points.channels[old_channel_size + 3].name = "curvatures";
00690 for (unsigned int d = old_channel_size; d < points.channels.size (); d++)
00691 points.channels[d].values.resize (points.points.size ());
00692
00693
00694 cloud_kdtree::KdTree *kdtree = new cloud_kdtree::KdTreeANN (points, point_indices);
00695
00696
00697 vector<vector<int> > points_k_indices (point_indices.size ());
00698 vector<float> distances;
00699
00700
00701 for (unsigned int i = 0; i < point_indices.size (); i++)
00702 {
00703
00704 kdtree->radiusSearch (points.points[point_indices.at (i)], 0.025, points_k_indices[i], distances);
00705 }
00706
00707 #pragma omp parallel for schedule(dynamic)
00708 for (int i = 0; i < (int)point_indices.size (); i++)
00709 {
00710
00711 Eigen::Vector4d plane_parameters;
00712 double curvature;
00713
00714 for (int j = 0; j < (int)points_k_indices[i].size (); j++)
00715 points_k_indices[i][j] = point_indices.at (points_k_indices[i][j]);
00716
00717 cloud_geometry::nearest::computePointNormal (points, points_k_indices[i], plane_parameters, curvature);
00718
00719 cloud_geometry::angles::flipNormalTowardsViewpoint (plane_parameters, points.points[point_indices.at (i)], viewpoint_cloud);
00720
00721 points.channels[old_channel_size + 0].values[point_indices.at (i)] = plane_parameters (0);
00722 points.channels[old_channel_size + 1].values[point_indices.at (i)] = plane_parameters (1);
00723 points.channels[old_channel_size + 2].values[point_indices.at (i)] = plane_parameters (2);
00724 points.channels[old_channel_size + 3].values[point_indices.at (i)] = curvature;
00725 }
00726
00727 delete kdtree;
00728 }
00729
00731
00737 void
00738 estimatePointNormals (const sensor_msgs::PointCloud &points, sensor_msgs::PointCloud &points_down, int k, const geometry_msgs::PointStamped &viewpoint_cloud)
00739 {
00740 int nr_points = points_down.points.size ();
00741
00742 points_down.channels.resize (4);
00743 points_down.channels[0].name = "nx";
00744 points_down.channels[1].name = "ny";
00745 points_down.channels[2].name = "nz";
00746 points_down.channels[3].name = "curvatures";
00747 for (unsigned int d = 0; d < points_down.channels.size (); d++)
00748 points_down.channels[d].values.resize (nr_points);
00749
00750 cloud_kdtree::KdTree *kdtree = new cloud_kdtree::KdTreeANN (points);
00751
00752
00753 vector<vector<int> > points_k_indices (nr_points);
00754 vector<float> distances;
00755
00756
00757 for (int i = 0; i < nr_points; i++)
00758 {
00759
00760
00761
00762 kdtree->radiusSearch (points_down.points[i], 0.025, points_k_indices[i], distances);
00763 }
00764
00765
00766 for (int i = 0; i < nr_points; i++)
00767 {
00768
00769 Eigen::Vector4d plane_parameters;
00770 double curvature;
00771 cloud_geometry::nearest::computePointNormal (points, points_k_indices[i], plane_parameters, curvature);
00772
00773 cloud_geometry::angles::flipNormalTowardsViewpoint (plane_parameters, points_down.points[i], viewpoint_cloud);
00774
00775 points_down.channels[0].values[i] = plane_parameters (0);
00776 points_down.channels[1].values[i] = plane_parameters (1);
00777 points_down.channels[2].values[i] = plane_parameters (2);
00778 points_down.channels[3].values[i] = curvature;
00779 }
00780
00781 delete kdtree;
00782 }
00783
00785
00793 int
00794 fitSACOrientedLine (sensor_msgs::PointCloud &points, const std::vector<int> &indices,
00795 double dist_thresh, const geometry_msgs::Point32 &axis, double eps_angle, std::vector<int> &line_inliers)
00796 {
00797 if (indices.size () < 2)
00798 {
00799 line_inliers.resize (0);
00800 return (-1);
00801 }
00802
00803
00804 sample_consensus::SACModelOrientedLine *model = new sample_consensus::SACModelOrientedLine ();
00805 sample_consensus::SAC *sac = new sample_consensus::RANSAC (model, dist_thresh);
00806 sac->setMaxIterations (100);
00807 model->setDataSet (&points, indices);
00808 model->setAxis (axis);
00809 model->setEpsAngle (eps_angle);
00810
00811 vector<double> coeff;
00812
00813 if (sac->computeModel ())
00814 {
00815 sac->computeCoefficients (coeff);
00816
00817 line_inliers = sac->getInliers ();
00818 }
00819 else
00820 {
00821 ROS_ERROR ("Could not compute an oriented line model.");
00822 return (-1);
00823 }
00824
00825 sort (line_inliers.begin (), line_inliers.end ());
00826 delete sac;
00827 delete model;
00828 return (0);
00829 }
00830
00832
00839 int
00840 fitSACOrientedLine (sensor_msgs::PointCloud &points,
00841 double dist_thresh, const geometry_msgs::Point32 &axis, double eps_angle, std::vector<int> &line_inliers)
00842 {
00843 if (points.points.size () < 2)
00844 {
00845 line_inliers.resize (0);
00846 return (-1);
00847 }
00848
00849
00850 sample_consensus::SACModelOrientedLine *model = new sample_consensus::SACModelOrientedLine ();
00851 sample_consensus::SAC *sac = new sample_consensus::RANSAC (model, dist_thresh);
00852 sac->setMaxIterations (100);
00853 model->setDataSet (&points);
00854 model->setAxis (axis);
00855 model->setEpsAngle (eps_angle);
00856
00857
00858 vector<double> coeff;
00859 if (sac->computeModel ())
00860 {
00861 sac->computeCoefficients (coeff);
00862 line_inliers = sac->getInliers ();
00863 }
00864 else
00865 {
00866 ROS_ERROR ("Could not compute an oriented line model.");
00867 return (-1);
00868 }
00869 sort (line_inliers.begin (), line_inliers.end ());
00870 delete sac;
00871 delete model;
00872 return (0);
00873 }
00874
00876
00883 void
00884 growCurrentCluster (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, const std::vector<int> &cluster,
00885 std::vector<int> &inliers, double dist_thresh)
00886 {
00887
00888 inliers.resize (cluster.size ());
00889 for (unsigned int i = 0; i < cluster.size (); i++)
00890 inliers[i] = cluster.at (i);
00891
00892 if (indices.size () < 2)
00893 {
00894 ROS_WARN ("[growCurrentCluster] Less than 2 points found in this cluster. Exiting...");
00895 return;
00896 }
00897 ROS_DEBUG ("[growCurrentCluster] Creating Kd-Tree with %d points for a %d-points cluster.", (int)indices.size (), (int)cluster.size ());
00898
00899
00900 cloud_kdtree::KdTree *kdtree = new cloud_kdtree::KdTreeANN (points, indices);
00901
00902
00903 vector<float> distances;
00904 for (unsigned int i = 0; i < cluster.size (); i++)
00905 {
00906 vector<int> points_k_indices;
00907
00908 kdtree->radiusSearch (points.points[cluster.at (i)], dist_thresh, points_k_indices, distances);
00909
00910 if (points_k_indices.size () == 0)
00911 continue;
00912 int old_size = inliers.size ();
00913 inliers.resize (old_size + points_k_indices.size ());
00914 for (unsigned int j = 0; j < points_k_indices.size (); j++)
00915 inliers[old_size + j] = indices.at (points_k_indices[j]);
00916 }
00917 sort (inliers.begin (), inliers.end ());
00918 inliers.erase (unique (inliers.begin (), inliers.end ()), inliers.end ());
00919
00920
00921 delete kdtree;
00922 }