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