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 <stereo_wall_detection/geometry/angles.h>
00034 #include <stereo_wall_detection/geometry/nearest.h>
00035 #include <stereo_wall_detection/geometry/point.h>
00036 #include <stereo_wall_detection/geometry/statistics.h>
00037
00038 #include <stereo_wall_detection/kdtree/kdtree.h>
00039 #include <stereo_wall_detection/kdtree/kdtree_ann.h>
00040 #include <Eigen/Eigenvalues>
00041
00042
00043 namespace cloud_geometry
00044 {
00045
00046 namespace nearest
00047 {
00048
00050
00054 void
00055 computeCentroid (const sensor_msgs::PointCloud &points, sensor_msgs::PointCloud ¢roid)
00056 {
00057
00058 centroid.points.resize (1);
00059 centroid.points[0].x = centroid.points[0].y = centroid.points[0].z = 0;
00060 centroid.channels.resize (points.channels.size ());
00061 for (unsigned int d = 0; d < points.channels.size (); d++)
00062 {
00063 centroid.channels[d].name = points.channels[d].name;
00064 centroid.channels[d].values.resize (1);
00065 }
00066
00067
00068 for (unsigned int i = 0; i < points.points.size (); i++)
00069 {
00070 centroid.points[0].x += points.points[i].x;
00071 centroid.points[0].y += points.points[i].y;
00072 centroid.points[0].z += points.points[i].z;
00073
00074 for (unsigned int d = 0; d < points.channels.size (); d++)
00075 centroid.channels[d].values[0] += points.channels[d].values[i];
00076 }
00077
00078 centroid.points[0].x /= points.points.size ();
00079 centroid.points[0].y /= points.points.size ();
00080 centroid.points[0].z /= points.points.size ();
00081 for (unsigned int d = 0; d < points.channels.size (); d++)
00082 centroid.channels[d].values[0] /= points.points.size ();
00083 }
00084
00086
00091 void
00092 computeCentroid (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, sensor_msgs::PointCloud ¢roid)
00093 {
00094
00095 centroid.points.resize (1);
00096 centroid.points[0].x = centroid.points[0].y = centroid.points[0].z = 0;
00097 centroid.channels.resize (points.channels.size ());
00098 for (unsigned int d = 0; d < points.channels.size (); d++)
00099 {
00100 centroid.channels[d].name = points.channels[d].name;
00101 centroid.channels[d].values.resize (1);
00102 }
00103
00104
00105 for (unsigned int i = 0; i < indices.size (); i++)
00106 {
00107 centroid.points[0].x += points.points.at (indices.at (i)).x;
00108 centroid.points[0].y += points.points.at (indices.at (i)).y;
00109 centroid.points[0].z += points.points.at (indices.at (i)).z;
00110
00111 for (unsigned int d = 0; d < points.channels.size (); d++)
00112 centroid.channels[d].values[0] += points.channels[d].values.at (indices.at (i));
00113 }
00114
00115 centroid.points[0].x /= indices.size ();
00116 centroid.points[0].y /= indices.size ();
00117 centroid.points[0].z /= indices.size ();
00118 for (unsigned int d = 0; d < points.channels.size (); d++)
00119 centroid.channels[d].values[0] /= indices.size ();
00120 }
00121
00123
00128 void
00129 computePatchEigen (const sensor_msgs::PointCloud &points, Eigen::Matrix3d &eigen_vectors, Eigen::Vector3d &eigen_values)
00130 {
00131 geometry_msgs::Point32 centroid;
00132
00133 Eigen::Matrix3d covariance_matrix;
00134 computeCovarianceMatrix (points, covariance_matrix, centroid);
00135
00136
00137 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> ei_symm (covariance_matrix);
00138 eigen_vectors = ei_symm.eigenvectors ();
00139 eigen_values = ei_symm.eigenvalues ();
00140
00141 }
00142
00144
00150 void
00151 computePatchEigen (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, Eigen::Matrix3d &eigen_vectors, Eigen::Vector3d &eigen_values)
00152 {
00153 geometry_msgs::Point32 centroid;
00154
00155 Eigen::Matrix3d covariance_matrix;
00156 computeCovarianceMatrix (points, indices, covariance_matrix, centroid);
00157
00158
00159 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> ei_symm (covariance_matrix);
00160 eigen_values = ei_symm.eigenvalues ();
00161 eigen_vectors = ei_symm.eigenvectors ();
00162 }
00163
00165
00171 void
00172 computePatchEigenNormalized (const sensor_msgs::PointCloud &points, Eigen::Matrix3d &eigen_vectors, Eigen::Vector3d &eigen_values, geometry_msgs::Point32& centroid)
00173 {
00174
00175
00176 Eigen::Matrix3d covariance_matrix;
00177 computeCovarianceMatrix (points, covariance_matrix, centroid);
00178
00179
00180 for (unsigned int i = 0 ; i < 3 ; i++)
00181 {
00182 for (unsigned int j = 0 ; j < 3 ; j++)
00183 {
00184 covariance_matrix(i, j) /= static_cast<double> (points.points.size ());
00185 }
00186 }
00187
00188
00189 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> ei_symm (covariance_matrix);
00190 eigen_values = ei_symm.eigenvalues ();
00191 eigen_vectors = ei_symm.eigenvectors ();
00192 }
00193
00195
00202 void
00203 computePatchEigenNormalized (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, Eigen::Matrix3d &eigen_vectors, Eigen::Vector3d &eigen_values, geometry_msgs::Point32& centroid)
00204 {
00205
00206
00207 Eigen::Matrix3d covariance_matrix;
00208 computeCovarianceMatrix (points, indices, covariance_matrix, centroid);
00209
00210
00211 for (unsigned int i = 0 ; i < 3 ; i++)
00212 {
00213 for (unsigned int j = 0 ; j < 3 ; j++)
00214 {
00215 covariance_matrix(i, j) /= static_cast<double> (indices.size ());
00216 }
00217 }
00218
00219
00220
00221 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> ei_symm (covariance_matrix);
00222 eigen_values = ei_symm.eigenvalues ();
00223 eigen_vectors = ei_symm.eigenvectors ();
00224 }
00225
00227
00236 void
00237 computePointNormal (const sensor_msgs::PointCloud &points, Eigen::Vector4d &plane_parameters, double &curvature)
00238 {
00239 geometry_msgs::Point32 centroid;
00240
00241 Eigen::Matrix3d covariance_matrix;
00242 computeCovarianceMatrix (points, covariance_matrix, centroid);
00243
00244
00245 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> ei_symm (covariance_matrix);
00246 Eigen::Vector3d eigen_values = ei_symm.eigenvalues ();
00247 Eigen::Matrix3d eigen_vectors = ei_symm.eigenvectors ();
00248
00249
00250 double norm = sqrt ( eigen_vectors (0, 0) * eigen_vectors (0, 0) +
00251 eigen_vectors (0, 1) * eigen_vectors (0, 1) +
00252 eigen_vectors (0, 2) * eigen_vectors (0, 2));
00253 plane_parameters (0) = eigen_vectors (0, 0) / norm;
00254 plane_parameters (1) = eigen_vectors (0, 1) / norm;
00255 plane_parameters (2) = eigen_vectors (0, 2) / norm;
00256
00257
00258 plane_parameters (3) = -1 * (plane_parameters (0) * centroid.x + plane_parameters (1) * centroid.y + plane_parameters (2) * centroid.z);
00259
00260
00261 curvature = fabs ( eigen_values (0) / (eigen_values (0) + eigen_values (1) + eigen_values (2)) );
00262 }
00263
00265
00275 void
00276 computePointNormal (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, Eigen::Vector4d &plane_parameters, double &curvature)
00277 {
00278 geometry_msgs::Point32 centroid;
00279
00280 Eigen::Matrix3d covariance_matrix;
00281 computeCovarianceMatrix (points, indices, covariance_matrix, centroid);
00282
00283
00284 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> ei_symm (covariance_matrix);
00285 Eigen::Vector3d eigen_values = ei_symm.eigenvalues ();
00286 Eigen::Matrix3d eigen_vectors = ei_symm.eigenvectors ();
00287
00288
00289
00290 double norm = sqrt ( eigen_vectors (0, 0) * eigen_vectors (0, 0) +
00291 eigen_vectors (1, 0) * eigen_vectors (1, 0) +
00292 eigen_vectors (2, 0) * eigen_vectors (2, 0));
00293 plane_parameters (0) = eigen_vectors (0, 0) / norm;
00294 plane_parameters (1) = eigen_vectors (1, 0) / norm;
00295 plane_parameters (2) = eigen_vectors (2, 0) / norm;
00296
00297
00298 plane_parameters (3) = -1 * (plane_parameters (0) * centroid.x + plane_parameters (1) * centroid.y + plane_parameters (2) * centroid.z);
00299
00300
00301 curvature = fabs ( eigen_values (0) / (eigen_values (0) + eigen_values (1) + eigen_values (2)) );
00302 }
00303
00305
00315 void
00316 computePointNormal (const sensor_msgs::PointCloudConstPtr &points, const std::vector<int> &indices, Eigen::Vector4d &plane_parameters, double &curvature)
00317 {
00318 geometry_msgs::Point32 centroid;
00319
00320 Eigen::Matrix3d covariance_matrix;
00321 computeCovarianceMatrix (points, indices, covariance_matrix, centroid);
00322
00323
00324 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> ei_symm (covariance_matrix);
00325 Eigen::Vector3d eigen_values = ei_symm.eigenvalues ();
00326 Eigen::Matrix3d eigen_vectors = ei_symm.eigenvectors ();
00327
00328
00329
00330 double norm = sqrt ( eigen_vectors (0, 0) * eigen_vectors (0, 0) +
00331 eigen_vectors (1, 0) * eigen_vectors (1, 0) +
00332 eigen_vectors (2, 0) * eigen_vectors (2, 0));
00333 plane_parameters (0) = eigen_vectors (0, 0) / norm;
00334 plane_parameters (1) = eigen_vectors (1, 0) / norm;
00335 plane_parameters (2) = eigen_vectors (2, 0) / norm;
00336
00337
00338 plane_parameters (3) = -1 * (plane_parameters (0) * centroid.x + plane_parameters (1) * centroid.y + plane_parameters (2) * centroid.z);
00339
00340
00341 curvature = fabs ( eigen_values (0) / (eigen_values (0) + eigen_values (1) + eigen_values (2)) );
00342 }
00343
00344
00346
00352 void
00353 computeMomentInvariants (const sensor_msgs::PointCloud &points, double &j1, double &j2, double &j3)
00354 {
00355
00356 geometry_msgs::Point32 centroid;
00357 computeCentroid (points, centroid);
00358
00359
00360 sensor_msgs::PointCloud points_c;
00361 points_c.points.resize (points.points.size ());
00362 for (unsigned int i = 0; i < points.points.size (); i++)
00363 {
00364 points_c.points[i].x = points.points[i].x - centroid.x;
00365 points_c.points[i].y = points.points[i].y - centroid.y;
00366 points_c.points[i].z = points.points[i].z - centroid.z;
00367 }
00368
00369 double mu200 = cloud_geometry::statistics::computeCentralizedMoment (points_c, 2.0, 0.0, 0.0);
00370 double mu020 = cloud_geometry::statistics::computeCentralizedMoment (points_c, 0.0, 2.0, 0.0);
00371 double mu002 = cloud_geometry::statistics::computeCentralizedMoment (points_c, 0.0, 0.0, 2.0);
00372 double mu110 = cloud_geometry::statistics::computeCentralizedMoment (points_c, 1.0, 1.0, 0.0);
00373 double mu101 = cloud_geometry::statistics::computeCentralizedMoment (points_c, 1.0, 0.0, 1.0);
00374 double mu011 = cloud_geometry::statistics::computeCentralizedMoment (points_c, 0.0, 1.0, 1.0);
00375
00376 j1 = mu200 + mu020 + mu002;
00377 j2 = mu200*mu020 + mu200*mu002 + mu020*mu002 - mu110*mu110 - mu101*mu101 - mu011*mu011;
00378 j3 = mu200*mu020*mu002 + 2*mu110*mu101*mu011 - mu002*mu110*mu110 - mu020*mu101*mu101 - mu200*mu011*mu011;
00379 }
00380
00382
00389 void
00390 computeMomentInvariants (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, double &j1, double &j2, double &j3)
00391 {
00392
00393 geometry_msgs::Point32 centroid;
00394 computeCentroid (points, indices, centroid);
00395
00396
00397 sensor_msgs::PointCloud points_c;
00398 points_c.points.resize (indices.size ());
00399 for (unsigned int i = 0; i < indices.size (); i++)
00400 {
00401 points_c.points[i].x = points.points.at (indices.at (i)).x - centroid.x;
00402 points_c.points[i].y = points.points.at (indices.at (i)).y - centroid.y;
00403 points_c.points[i].z = points.points.at (indices.at (i)).z - centroid.z;
00404 }
00405
00406 double mu200 = cloud_geometry::statistics::computeCentralizedMoment (points_c, 2.0, 0.0, 0.0);
00407 double mu020 = cloud_geometry::statistics::computeCentralizedMoment (points_c, 0.0, 2.0, 0.0);
00408 double mu002 = cloud_geometry::statistics::computeCentralizedMoment (points_c, 0.0, 0.0, 2.0);
00409 double mu110 = cloud_geometry::statistics::computeCentralizedMoment (points_c, 1.0, 1.0, 0.0);
00410 double mu101 = cloud_geometry::statistics::computeCentralizedMoment (points_c, 1.0, 0.0, 1.0);
00411 double mu011 = cloud_geometry::statistics::computeCentralizedMoment (points_c, 0.0, 1.0, 1.0);
00412
00413 j1 = mu200 + mu020 + mu002;
00414 j2 = mu200*mu020 + mu200*mu002 + mu020*mu002 - mu110*mu110 - mu101*mu101 - mu011*mu011;
00415 j3 = mu200*mu020*mu002 + 2*mu110*mu101*mu011 - mu002*mu110*mu110 - mu020*mu101*mu101 - mu200*mu011*mu011;
00416 }
00417
00419
00428 bool
00429 isBoundaryPoint (const sensor_msgs::PointCloud &points, int q_idx, const std::vector<int> &neighbors,
00430 const Eigen::Vector3d& u, const Eigen::Vector3d& v, double angle_threshold)
00431 {
00432 if (neighbors.size () < 3)
00433 return (false);
00434 double uvn_nn[2];
00435
00436 std::vector<double> angles;
00437 angles.reserve (neighbors.size ());
00438 for (unsigned int i = 0; i < neighbors.size (); i++)
00439 {
00440 uvn_nn[0] = (points.points.at (neighbors.at (i)).x - points.points.at (q_idx).x) * u (0) +
00441 (points.points.at (neighbors.at (i)).y - points.points.at (q_idx).y) * u (1) +
00442 (points.points.at (neighbors.at (i)).z - points.points.at (q_idx).z) * u (2);
00443 uvn_nn[1] = (points.points.at (neighbors.at (i)).x - points.points.at (q_idx).x) * v (0) +
00444 (points.points.at (neighbors.at (i)).y - points.points.at (q_idx).y) * v (1) +
00445 (points.points.at (neighbors.at (i)).z - points.points.at (q_idx).z) * v (2);
00446 if (uvn_nn[0] == 0 && uvn_nn[1] == 0)
00447 continue;
00448 angles.push_back (cloud_geometry::angles::getAngle2D (uvn_nn));
00449 }
00450 sort (angles.begin (), angles.end ());
00451
00452
00453 double max_dif = DBL_MIN, dif;
00454 for (unsigned int i = 0; i < angles.size () - 1; i++)
00455 {
00456 dif = angles[i + 1] - angles[i];
00457 if (max_dif < dif)
00458 max_dif = dif;
00459 }
00460
00461 dif = 2 * M_PI - angles[angles.size () - 1] + angles[0];
00462 if (max_dif < dif)
00463 max_dif = dif;
00464
00465
00466 if (max_dif > angle_threshold)
00467 return (true);
00468 else
00469 return (false);
00470 }
00471
00473
00480 void
00481 computePointCloudNormals (sensor_msgs::PointCloud &points, const sensor_msgs::PointCloud &surface, int k,
00482 const geometry_msgs::PointStamped &viewpoint)
00483 {
00484 int nr_points = points.points.size ();
00485 int orig_dims = points.channels.size ();
00486 points.channels.resize (orig_dims + 4);
00487 points.channels[orig_dims + 0].name = "nx";
00488 points.channels[orig_dims + 1].name = "ny";
00489 points.channels[orig_dims + 2].name = "nz";
00490 points.channels[orig_dims + 3].name = "curvatures";
00491 for (unsigned int d = orig_dims; d < points.channels.size (); d++)
00492 points.channels[d].values.resize (nr_points);
00493
00494 cloud_kdtree::KdTree *kdtree = new cloud_kdtree::KdTreeANN (surface);
00495
00496 #pragma omp parallel for schedule(dynamic)
00497 for (int i = 0; i < nr_points; i++)
00498 {
00499 std::vector<int> nn_indices;
00500 std::vector<float> nn_distances;
00501 kdtree->nearestKSearch (points.points[i], k, nn_indices, nn_distances);
00502
00503 Eigen::Vector4d plane_parameters;
00504 double curvature;
00505 computePointNormal (surface, nn_indices, plane_parameters, curvature);
00506
00507 cloud_geometry::angles::flipNormalTowardsViewpoint (plane_parameters, points.points[i], viewpoint);
00508
00509 points.channels[orig_dims + 0].values[i] = plane_parameters (0);
00510 points.channels[orig_dims + 1].values[i] = plane_parameters (1);
00511 points.channels[orig_dims + 2].values[i] = plane_parameters (2);
00512 points.channels[orig_dims + 3].values[i] = curvature;
00513 }
00514 delete kdtree;
00515 }
00516
00518
00525 void
00526 computePointCloudNormals (sensor_msgs::PointCloud &points, const sensor_msgs::PointCloud &surface, double radius,
00527 const geometry_msgs::PointStamped &viewpoint)
00528 {
00529 int nr_points = points.points.size ();
00530 int orig_dims = points.channels.size ();
00531 points.channels.resize (orig_dims + 4);
00532 points.channels[orig_dims + 0].name = "nx";
00533 points.channels[orig_dims + 1].name = "ny";
00534 points.channels[orig_dims + 2].name = "nz";
00535 points.channels[orig_dims + 3].name = "curvatures";
00536 for (unsigned int d = orig_dims; d < points.channels.size (); d++)
00537 points.channels[d].values.resize (nr_points);
00538
00539 cloud_kdtree::KdTree *kdtree = new cloud_kdtree::KdTreeANN (surface);
00540
00541 #pragma omp parallel for schedule(dynamic)
00542 for (int i = 0; i < nr_points; i++)
00543 {
00544 std::vector<int> nn_indices;
00545 std::vector<float> nn_distances;
00546 kdtree->radiusSearch (points.points[i], radius, nn_indices, nn_distances);
00547
00548 Eigen::Vector4d plane_parameters;
00549 double curvature;
00550 computePointNormal (surface, nn_indices, plane_parameters, curvature);
00551
00552 cloud_geometry::angles::flipNormalTowardsViewpoint (plane_parameters, points.points[i], viewpoint);
00553
00554 points.channels[orig_dims + 0].values[i] = plane_parameters (0);
00555 points.channels[orig_dims + 1].values[i] = plane_parameters (1);
00556 points.channels[orig_dims + 2].values[i] = plane_parameters (2);
00557 points.channels[orig_dims + 3].values[i] = curvature;
00558 }
00559 delete kdtree;
00560 }
00561
00563
00568 void
00569 computePointCloudNormals (sensor_msgs::PointCloud &points, int k, const geometry_msgs::PointStamped &viewpoint)
00570 {
00571 int nr_points = points.points.size ();
00572 int orig_dims = points.channels.size ();
00573 points.channels.resize (orig_dims + 4);
00574 points.channels[orig_dims + 0].name = "nx";
00575 points.channels[orig_dims + 1].name = "ny";
00576 points.channels[orig_dims + 2].name = "nz";
00577 points.channels[orig_dims + 3].name = "curvatures";
00578 for (unsigned int d = orig_dims; d < points.channels.size (); d++)
00579 points.channels[d].values.resize (nr_points);
00580
00581
00582 ros::Time ts = ros::Time::now();
00583 cloud_kdtree::KdTree *kdtree = new cloud_kdtree::KdTreeANN (points);
00584 ROS_INFO("KdTree created in %f seconds", (ros::Time::now () - ts).toSec ());
00585
00586 double total_search_time = 0.0, total_normal_time = 0.0;
00587
00588 #pragma omp parallel for schedule(dynamic)
00589 for (int i = 0; i < nr_points; i++)
00590 {
00591 std::vector<int> nn_indices;
00592 std::vector<float> nn_distances;
00593
00594 ros::Time ts_search = ros::Time::now();
00595 kdtree->nearestKSearch (points.points[i], k, nn_indices, nn_distances);
00596 total_search_time += (ros::Time::now () - ts_search).toSec ();
00597
00598 Eigen::Vector4d plane_parameters;
00599 double curvature;
00600
00601 ros::Time ts_normal = ros::Time::now();
00602 computePointNormal (points, nn_indices, plane_parameters, curvature);
00603 total_normal_time += (ros::Time::now () - ts_normal).toSec ();
00604
00605 cloud_geometry::angles::flipNormalTowardsViewpoint (plane_parameters, points.points[i], viewpoint);
00606
00607 points.channels[orig_dims + 0].values[i] = plane_parameters (0);
00608 points.channels[orig_dims + 1].values[i] = plane_parameters (1);
00609 points.channels[orig_dims + 2].values[i] = plane_parameters (2);
00610 points.channels[orig_dims + 3].values[i] = curvature;
00611 }
00612 ROS_INFO("Breakdown: %f seconds to search, %f seconds to compute normals", total_search_time, total_normal_time);
00613
00614 delete kdtree;
00615 }
00616
00618
00623 void
00624 computePointCloudNormals (sensor_msgs::PointCloud &points, double radius, const geometry_msgs::PointStamped &viewpoint)
00625 {
00626 int nr_points = points.points.size ();
00627 int orig_dims = points.channels.size ();
00628 points.channels.resize (orig_dims + 4);
00629 points.channels[orig_dims + 0].name = "nx";
00630 points.channels[orig_dims + 1].name = "ny";
00631 points.channels[orig_dims + 2].name = "nz";
00632 points.channels[orig_dims + 3].name = "curvatures";
00633 for (unsigned int d = orig_dims; d < points.channels.size (); d++)
00634 points.channels[d].values.resize (nr_points);
00635
00636 cloud_kdtree::KdTree *kdtree = new cloud_kdtree::KdTreeANN (points);
00637
00638 #pragma omp parallel for schedule(dynamic)
00639 for (int i = 0; i < nr_points; i++)
00640 {
00641 std::vector<int> nn_indices;
00642 std::vector<float> nn_distances;
00643 kdtree->radiusSearch (points.points[i], radius, nn_indices, nn_distances);
00644
00645 Eigen::Vector4d plane_parameters;
00646 double curvature;
00647 computePointNormal (points, nn_indices, plane_parameters, curvature);
00648
00649 cloud_geometry::angles::flipNormalTowardsViewpoint (plane_parameters, points.points[i], viewpoint);
00650
00651 points.channels[orig_dims + 0].values[i] = plane_parameters (0);
00652 points.channels[orig_dims + 1].values[i] = plane_parameters (1);
00653 points.channels[orig_dims + 2].values[i] = plane_parameters (2);
00654 points.channels[orig_dims + 3].values[i] = curvature;
00655 }
00656 delete kdtree;
00657 }
00658
00660
00676 void
00677 computeOrganizedPointCloudNormals (sensor_msgs::PointCloud &points, const sensor_msgs::PointCloud &surface,
00678 int k, int downsample_factor, int width, int height, double max_z,
00679 const geometry_msgs::Point32 &viewpoint)
00680 {
00681
00682 int nr_points = lrint (ceil (width / (double)downsample_factor)) *
00683 lrint (ceil (height / (double)downsample_factor));
00684 int orig_dims = points.channels.size ();
00685 points.channels.resize (orig_dims + 4);
00686 points.channels[orig_dims + 0].name = "nx";
00687 points.channels[orig_dims + 1].name = "ny";
00688 points.channels[orig_dims + 2].name = "nz";
00689 points.channels[orig_dims + 3].name = "curvatures";
00690 points.points.resize (nr_points);
00691
00692 for (unsigned int d = orig_dims; d < points.channels.size (); d++)
00693 points.channels[d].values.resize (nr_points);
00694
00695
00696 std::vector<int> nn_indices ((k + k + 1) * (k + k + 1));
00697 Eigen::Vector4d plane_parameters;
00698 double curvature;
00699
00700 int j = 0;
00701 #pragma omp parallel for schedule(dynamic)
00702 for (int i = 0; i < (int)surface.points.size (); i++)
00703 {
00704
00705 int u = i / width;
00706 int v = i % width;
00707
00708
00709 if ((u % downsample_factor != 0) || (v % downsample_factor != 0))
00710 continue;
00711
00712
00713 points.points[j] = surface.points[i];
00714
00715
00716 int l = 0;
00717 for (int x = -k; x < k+1; x++)
00718 {
00719 for (int y = -k; y < k+1; y++)
00720 {
00721 int idx = (u+x) * width + (v+y);
00722 if (idx == i)
00723 continue;
00724
00725 if (idx < 0 || idx >= (int)surface.points.size ())
00726 continue;
00727
00728 if (max_z != -1)
00729 {
00730 if ( fabs (points.points[j].z - surface.points[idx].z) < max_z )
00731 nn_indices[l++] = idx;
00732 }
00733 else
00734 nn_indices[l++] = idx;
00735 }
00736 }
00737 nn_indices.resize (l);
00738 if (nn_indices.size () < 4)
00739 {
00740
00741 continue;
00742 }
00743
00744
00745 cloud_geometry::nearest::computePointNormal (surface, nn_indices, plane_parameters, curvature);
00746 cloud_geometry::angles::flipNormalTowardsViewpoint (plane_parameters, surface.points[i], viewpoint);
00747
00748 points.channels[orig_dims + 0].values[j] = plane_parameters (0);
00749 points.channels[orig_dims + 1].values[j] = plane_parameters (1);
00750 points.channels[orig_dims + 2].values[j] = plane_parameters (2);
00751 points.channels[orig_dims + 3].values[j] = curvature;
00752 j++;
00753 }
00754 }
00755
00757
00773 void
00774 computeOrganizedPointCloudNormals (sensor_msgs::PointCloud &points, const sensor_msgs::PointCloudConstPtr &surface,
00775 int k, int downsample_factor, int width, int height, double max_z,
00776 const geometry_msgs::Point32 &viewpoint)
00777 {
00778
00779 int nr_points = lrint (ceil (width / (double)downsample_factor)) *
00780 lrint (ceil (height / (double)downsample_factor));
00781 int orig_dims = points.channels.size ();
00782 points.channels.resize (orig_dims + 4);
00783 points.channels[orig_dims + 0].name = "nx";
00784 points.channels[orig_dims + 1].name = "ny";
00785 points.channels[orig_dims + 2].name = "nz";
00786 points.channels[orig_dims + 3].name = "curvatures";
00787 points.points.resize (nr_points);
00788
00789 for (unsigned int d = orig_dims; d < points.channels.size (); d++)
00790 points.channels[d].values.resize (nr_points);
00791
00792
00793 std::vector<int> nn_indices ((k + k + 1) * (k + k + 1));
00794 Eigen::Vector4d plane_parameters;
00795 double curvature;
00796
00797 int j = 0;
00798 #pragma omp parallel for schedule(dynamic)
00799 for (int i = 0; i < (int)surface->points.size (); i++)
00800 {
00801
00802 int u = i / width;
00803 int v = i % width;
00804
00805
00806 if ((u % downsample_factor != 0) || (v % downsample_factor != 0))
00807 continue;
00808
00809
00810 points.points[j] = surface->points[i];
00811
00812
00813 int l = 0;
00814 for (int x = -k; x < k+1; x++)
00815 {
00816 for (int y = -k; y < k+1; y++)
00817 {
00818 int idx = (u+x) * width + (v+y);
00819 if (idx == i)
00820 continue;
00821
00822 if (idx < 0 || idx >= (int)surface->points.size ())
00823 continue;
00824
00825 if (max_z != -1)
00826 {
00827 if ( fabs (points.points[j].z - surface->points[idx].z) < max_z )
00828 nn_indices[l++] = idx;
00829 }
00830 else
00831 nn_indices[l++] = idx;
00832 }
00833 }
00834 nn_indices.resize (l);
00835 if (nn_indices.size () < 4)
00836 {
00837
00838 continue;
00839 }
00840
00841
00842 cloud_geometry::nearest::computePointNormal (surface, nn_indices, plane_parameters, curvature);
00843 cloud_geometry::angles::flipNormalTowardsViewpoint (plane_parameters, surface->points[i], viewpoint);
00844
00845 points.channels[orig_dims + 0].values[j] = plane_parameters (0);
00846 points.channels[orig_dims + 1].values[j] = plane_parameters (1);
00847 points.channels[orig_dims + 2].values[j] = plane_parameters (2);
00848 points.channels[orig_dims + 3].values[j] = curvature;
00849 j++;
00850 }
00851 }
00852
00854
00872 void
00873 computeOrganizedPointCloudNormalsWithFiltering (sensor_msgs::PointCloud &points, const sensor_msgs::PointCloud &surface,
00874 int k, int downsample_factor, int width, int height, double max_z,
00875 double min_angle, double max_angle,
00876 const geometry_msgs::Point32 &viewpoint)
00877 {
00878
00879 int nr_points = lrint (ceil (width / (double)downsample_factor)) *
00880 lrint (ceil (height / (double)downsample_factor));
00881 int orig_dims = points.channels.size ();
00882 points.channels.resize (orig_dims + 4);
00883 points.channels[orig_dims + 0].name = "nx";
00884 points.channels[orig_dims + 1].name = "ny";
00885 points.channels[orig_dims + 2].name = "nz";
00886 points.channels[orig_dims + 3].name = "curvatures";
00887 points.points.resize (nr_points);
00888
00889 for (unsigned int d = orig_dims; d < points.channels.size (); d++)
00890 points.channels[d].values.resize (nr_points);
00891
00892
00893 std::vector<int> nn_indices ((k + k + 1) * (k + k + 1));
00894 Eigen::Vector4d plane_parameters;
00895 double curvature;
00896
00897 int j = 0;
00898 #pragma omp parallel for schedule(dynamic)
00899 for (int i = 0; i < (int)surface.points.size (); i++)
00900 {
00901
00902 int u = i / width;
00903 int v = i % width;
00904
00905
00906 if ((u % downsample_factor != 0) || (v % downsample_factor != 0))
00907 continue;
00908
00909
00910 points.points[j] = surface.points[i];
00911
00912
00913 int l = 0;
00914 for (int x = -k; x < k+1; x++)
00915 {
00916 for (int y = -k; y < k+1; y++)
00917 {
00918 int idx = (u+x) * width + (v+y);
00919 if (idx == i)
00920 continue;
00921
00922
00923 if (idx < 0 || idx >= (int)surface.points.size ())
00924 continue;
00925
00926
00927 double angle = getAngleWithViewpoint (points.points[j].x, points.points[j].y, points.points[j].z,
00928 surface.points[idx].x, surface.points[idx].y, surface.points[idx].z,
00929 viewpoint.x, viewpoint.y, viewpoint.z);
00930 if (angle < min_angle || angle > max_angle)
00931 continue;
00932
00933
00934 if (max_z != -1)
00935 {
00936 if ( fabs (points.points[j].z - surface.points[idx].z) < max_z )
00937 nn_indices[l++] = idx;
00938 }
00939 else
00940 nn_indices[l++] = idx;
00941 }
00942 }
00943 nn_indices.resize (l);
00944 if (nn_indices.size () < 4)
00945 {
00946
00947 continue;
00948 }
00949
00950
00951 cloud_geometry::nearest::computePointNormal (surface, nn_indices, plane_parameters, curvature);
00952 cloud_geometry::angles::flipNormalTowardsViewpoint (plane_parameters, surface.points[i], viewpoint);
00953
00954 points.channels[orig_dims + 0].values[j] = plane_parameters (0);
00955 points.channels[orig_dims + 1].values[j] = plane_parameters (1);
00956 points.channels[orig_dims + 2].values[j] = plane_parameters (2);
00957 points.channels[orig_dims + 3].values[j] = curvature;
00958 j++;
00959 }
00960 }
00961
00963
00975 void
00976 filterJumpEdges (const sensor_msgs::PointCloud &points, sensor_msgs::PointCloud &points_filtered, int k, int width, int height,
00977 double min_angle, double max_angle, const geometry_msgs::Point32 &viewpoint)
00978 {
00979
00980 points_filtered.header = points.header;
00981 points_filtered.points.resize (points.points.size ());
00982 points_filtered.channels.resize (points.channels.size ());
00983 for (unsigned int d = 0; d < points.channels.size (); d++)
00984 {
00985 points_filtered.channels[d].name = points.channels[d].name;
00986 points_filtered.channels[d].values.resize (points.channels[d].values.size ());
00987 }
00988
00989 int j = 0;
00990 #pragma omp parallel for schedule(dynamic)
00991 for (int i = 0; i < (int)points.points.size (); i++)
00992 {
00993
00994 int u = i / width;
00995 int v = i % width;
00996
00997
00998 bool valid_point = true;
00999 for (int x = -k; x < k+1; x++)
01000 {
01001 if (!valid_point)
01002 break;
01003 for (int y = -k; y < k+1; y++)
01004 {
01005 int idx = (u+x) * width + (v+y);
01006 if (idx == i)
01007 continue;
01008
01009
01010 if (idx < 0 || idx >= (int)points.points.size ())
01011 continue;
01012
01013
01014 double angle = getAngleWithViewpoint (points.points[i].x, points.points[i].y, points.points[i].z,
01015 points.points[idx].x, points.points[idx].y, points.points[idx].z,
01016 viewpoint.x, viewpoint.y, viewpoint.z);
01017 if (angle < min_angle || angle > max_angle)
01018 {
01019 valid_point = false;
01020 break;
01021 }
01022
01023 }
01024 }
01025
01026 if (valid_point)
01027 {
01028
01029 points_filtered.points[j] = points.points[i];
01030 for (unsigned int d = 0; d < points.channels.size (); d++)
01031 points_filtered.channels[d].values[j] = points.channels[d].values[j];
01032 j++;
01033 }
01034 }
01035 points_filtered.points.resize (j);
01036 for (unsigned int d = 0; d < points.channels.size (); d++)
01037 points_filtered.channels[d].values.resize (j);
01038 }
01039
01041
01055 void
01056 extractEuclideanClusters (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, double tolerance,
01057 std::vector<std::vector<int> > &clusters,
01058 int nx_idx, int ny_idx, int nz_idx, double eps_angle, unsigned int min_pts_per_cluster)
01059 {
01060
01061 cloud_kdtree::KdTree* tree = new cloud_kdtree::KdTreeANN (points, indices);
01062
01063 int nr_points = indices.size ();
01064
01065 std::vector<bool> processed;
01066 processed.resize (nr_points, false);
01067
01068 std::vector<int> nn_indices;
01069 std::vector<float> nn_distances;
01070
01071 for (int i = 0; i < nr_points; i++)
01072 {
01073 if (processed[i])
01074 continue;
01075
01076 std::vector<int> seed_queue;
01077
01078 int sq_idx = 0;
01079 seed_queue.push_back (i);
01080
01081 processed[i] = true;
01082
01083 while (sq_idx < (int)seed_queue.size ())
01084 {
01085
01086 tree->radiusSearch (seed_queue.at (sq_idx), tolerance, nn_indices, nn_distances);
01087
01088 for (unsigned int j = 1; j < nn_indices.size (); j++)
01089 {
01090 if (processed.at (nn_indices[j]))
01091 continue;
01092
01093 processed[nn_indices[j]] = true;
01094 if (nx_idx != -1)
01095 {
01096
01097 double dot_p = points.channels[nx_idx].values[indices.at (i)] * points.channels[nx_idx].values[indices.at (nn_indices[j])] +
01098 points.channels[ny_idx].values[indices.at (i)] * points.channels[ny_idx].values[indices.at (nn_indices[j])] +
01099 points.channels[nz_idx].values[indices.at (i)] * points.channels[nz_idx].values[indices.at (nn_indices[j])];
01100 if ( fabs (acos (dot_p)) < eps_angle )
01101 {
01102 processed[nn_indices[j]] = true;
01103 seed_queue.push_back (nn_indices[j]);
01104 }
01105 }
01106
01107 else
01108 {
01109 processed[nn_indices[j]] = true;
01110 seed_queue.push_back (nn_indices[j]);
01111 }
01112 }
01113
01114 sq_idx++;
01115 }
01116
01117
01118 if (seed_queue.size () >= min_pts_per_cluster)
01119 {
01120 std::vector<int> r (seed_queue.size ());
01121 for (unsigned int j = 0; j < seed_queue.size (); j++)
01122 r[j] = indices.at (seed_queue[j]);
01123
01124 sort (r.begin (), r.end ());
01125 r.erase (unique (r.begin (), r.end ()), r.end ());
01126
01127 clusters.push_back (r);
01128 }
01129 }
01130
01131
01132 delete tree;
01133 }
01134
01136
01149 void
01150 extractEuclideanClusters (const sensor_msgs::PointCloud &points, double tolerance,
01151 std::vector<std::vector<int> > &clusters,
01152 int nx_idx, int ny_idx, int nz_idx, double eps_angle, unsigned int min_pts_per_cluster)
01153 {
01154
01155 cloud_kdtree::KdTree* tree = new cloud_kdtree::KdTreeANN (points);
01156
01157 int nr_points = points.points.size ();
01158
01159 std::vector<bool> processed;
01160 processed.resize (nr_points, false);
01161
01162 std::vector<int> nn_indices;
01163 std::vector<float> nn_distances;
01164
01165 for (int i = 0; i < nr_points; i++)
01166 {
01167 if (processed[i])
01168 continue;
01169
01170 std::vector<int> seed_queue;
01171 int sq_idx = 0;
01172 seed_queue.push_back (i);
01173
01174 processed[i] = true;
01175
01176 while (sq_idx < (int)seed_queue.size ())
01177 {
01178
01179 tree->radiusSearch (seed_queue.at (sq_idx), tolerance, nn_indices, nn_distances);
01180
01181 for (unsigned int j = 1; j < nn_indices.size (); j++)
01182 {
01183 if (processed.at (nn_indices[j]))
01184 continue;
01185
01186 processed[nn_indices[j]] = true;
01187 if (nx_idx != -1)
01188 {
01189
01190 double dot_p = points.channels[nx_idx].values[i] * points.channels[nx_idx].values[nn_indices[j]] +
01191 points.channels[ny_idx].values[i] * points.channels[ny_idx].values[nn_indices[j]] +
01192 points.channels[nz_idx].values[i] * points.channels[nz_idx].values[nn_indices[j]];
01193 if ( fabs (acos (dot_p)) < eps_angle )
01194 {
01195 processed[nn_indices[j]] = true;
01196 seed_queue.push_back (nn_indices[j]);
01197 }
01198 }
01199
01200 else
01201 {
01202 processed[nn_indices[j]] = true;
01203 seed_queue.push_back (nn_indices[j]);
01204 }
01205 }
01206
01207 sq_idx++;
01208 }
01209
01210
01211 if (seed_queue.size () >= min_pts_per_cluster)
01212 {
01213 std::vector<int> r (seed_queue.size ());
01214 for (unsigned int j = 0; j < seed_queue.size (); j++)
01215 r[j] = seed_queue[j];
01216
01217
01218 sort (r.begin (), r.end ());
01219 r.erase (unique (r.begin (), r.end ()), r.end ());
01220
01221 clusters.push_back (r);
01222 }
01223 }
01224
01225
01226 delete tree;
01227 }
01228
01229
01230 }
01231 }