Functions | |
| void | computeCentroid (const sensor_msgs::PointCloud &points, geometry_msgs::Point32 ¢roid) |
| Compute the centroid of a set of points and return it as a Point32 message. | |
| void | computeCentroid (const geometry_msgs::Polygon &poly, geometry_msgs::Point32 ¢roid) |
| Compute the centroid of a 3D polygon and return it as a Point32 message. | |
| void | computeCentroid (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, sensor_msgs::PointCloud ¢roid) |
| Compute the centroid of a set of points using their indices and return it as a PointCloud message with 1 value. | |
| void | computeCentroid (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, geometry_msgs::Point32 ¢roid) |
| Compute the centroid of a set of points using their indices and return it as a Point32 message. | |
| void | computeCentroid (const sensor_msgs::PointCloudConstPtr &points, const std::vector< int > &indices, geometry_msgs::Point32 ¢roid) |
| Compute the centroid of a set of points using their indices and return it as a Point32 message. | |
| void | computeCentroid (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, std::vector< double > ¢roid) |
| Compute the centroid of a set of points using their indices and return it as a Point32 message. | |
| void | computeCentroid (const sensor_msgs::PointCloud &points, sensor_msgs::PointCloud ¢roid) |
| Compute the centroid of a set of points and return it as a PointCloud message with 1 value. | |
| void | computeCentroid (const sensor_msgs::PointCloud &points, std::vector< int > &indices, sensor_msgs::PointCloud ¢roid) |
| void | computeCovarianceMatrix (const sensor_msgs::PointCloud &points, Eigen::Matrix3d &covariance_matrix, geometry_msgs::Point32 ¢roid) |
| Compute the 3x3 covariance matrix of a given set of points. The result is returned as a Eigen::Matrix3d. | |
| void | computeCovarianceMatrix (const sensor_msgs::PointCloud &points, Eigen::Matrix3d &covariance_matrix) |
| Compute the 3x3 covariance matrix of a given set of points. The result is returned as a Eigen::Matrix3d. | |
| void | computeCovarianceMatrix (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, Eigen::Matrix3d &covariance_matrix, geometry_msgs::Point32 ¢roid) |
| Compute the 3x3 covariance matrix of a given set of points using their indices. The result is returned as a Eigen::Matrix3d. | |
| void | computeCovarianceMatrix (const sensor_msgs::PointCloudConstPtr &points, const std::vector< int > &indices, Eigen::Matrix3d &covariance_matrix, geometry_msgs::Point32 ¢roid) |
| Compute the 3x3 covariance matrix of a given set of points using their indices. The result is returned as a Eigen::Matrix3d. | |
| void | computeCovarianceMatrix (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, Eigen::Matrix3d &covariance_matrix) |
| Compute the 3x3 covariance matrix of a given set of points using their indices. The result is returned as a Eigen::Matrix3d. | |
| void | computeMomentInvariants (const sensor_msgs::PointCloud &points, double &j1, double &j2, double &j3) |
| Compute the 3 moment invariants (j1, j2, j3) for a given set of points. | |
| void | computeMomentInvariants (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, double &j1, double &j2, double &j3) |
| Compute the 3 moment invariants (j1, j2, j3) for a given set of points, using their indices. | |
| void | computeOrganizedPointCloudNormals (sensor_msgs::PointCloud &points, const sensor_msgs::PointCloud &surface, int k, int downsample_factor, int width, int height, double max_z, const geometry_msgs::Point32 &viewpoint) |
| Estimate the point normals and surface curvatures for a given organized point cloud dataset (points) using the data from a different point cloud (surface) for least-squares planar estimation. | |
| void | computeOrganizedPointCloudNormals (sensor_msgs::PointCloud &points, const sensor_msgs::PointCloudConstPtr &surface, int k, int downsample_factor, int width, int height, double max_z, const geometry_msgs::Point32 &viewpoint) |
| Estimate the point normals and surface curvatures for a given organized point cloud dataset (points) using the data from a different point cloud (surface) for least-squares planar estimation. | |
| void | computeOrganizedPointCloudNormalsWithFiltering (sensor_msgs::PointCloud &points, const sensor_msgs::PointCloud &surface, int k, int downsample_factor, int width, int height, double max_z, double min_angle, double max_angle, const geometry_msgs::Point32 &viewpoint) |
| Estimate the point normals and surface curvatures for a given organized point cloud dataset (points) using the data from a different point cloud (surface) for least-squares planar estimation. | |
| void | computePatchEigen (const sensor_msgs::PointCloud &points, Eigen::Matrix3d &eigen_vectors, Eigen::Vector3d &eigen_values) |
| Compute the eigenvalues and eigenvectors of a given surface patch. | |
| void | computePatchEigen (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, Eigen::Matrix3d &eigen_vectors, Eigen::Vector3d &eigen_values) |
| Compute the eigenvalues and eigenvectors of a given surface patch. | |
| void | computePatchEigenNormalized (const sensor_msgs::PointCloud &points, Eigen::Matrix3d &eigen_vectors, Eigen::Vector3d &eigen_values, geometry_msgs::Point32 ¢roid) |
| Compute the eigenvalues and eigenvectors of a given surface patch from its normalized covariance matrix. | |
| void | computePatchEigenNormalized (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, Eigen::Matrix3d &eigen_vectors, Eigen::Vector3d &eigen_values, geometry_msgs::Point32 ¢roid) |
| Compute the eigenvalues and eigenvectors of a given surface patch from its normalized covariance matrix. | |
| void | computePointCloudNormals (sensor_msgs::PointCloud &points, const sensor_msgs::PointCloud &surface, int k, const geometry_msgs::PointStamped &viewpoint) |
| Estimate (in place) the point normals and surface curvatures for a given point cloud dataset (points) using the data from a different point cloud (surface) for least-squares planar estimation. | |
| void | computePointCloudNormals (sensor_msgs::PointCloud &points, const sensor_msgs::PointCloud &surface, double radius, const geometry_msgs::PointStamped &viewpoint) |
| Estimate (in place) the point normals and surface curvatures for a given point cloud dataset (points) using the data from a different point cloud (surface) for least-squares planar estimation. | |
| void | computePointCloudNormals (sensor_msgs::PointCloud &points, int k, const geometry_msgs::PointStamped &viewpoint) |
| Estimate (in place) the point normals and surface curvatures for a given point cloud dataset (points) | |
| void | computePointCloudNormals (sensor_msgs::PointCloud &points, double radius, const geometry_msgs::PointStamped &viewpoint) |
| Estimate (in place) the point normals and surface curvatures for a given point cloud dataset (points) | |
| void | computePointNormal (const sensor_msgs::PointCloud &points, Eigen::Vector4d &plane_parameters, double &curvature) |
| Compute the Least-Squares plane fit for a given set of points, and return the estimated plane parameters together with the surface curvature. | |
| void | computePointNormal (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, Eigen::Vector4d &plane_parameters, double &curvature) |
| Compute the Least-Squares plane fit for a given set of points, using their indices, and return the estimated plane parameters together with the surface curvature. | |
| void | computePointNormal (const sensor_msgs::PointCloudConstPtr &points, const std::vector< int > &indices, Eigen::Vector4d &plane_parameters, double &curvature) |
| Compute the Least-Squares plane fit for a given set of points, using their indices, and return the estimated plane parameters together with the surface curvature. | |
| void | extractEuclideanClusters (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, double tolerance, std::vector< std::vector< int > > &clusters, int nx_idx, int ny_idx, int nz_idx, double eps_angle, unsigned int min_pts_per_cluster) |
| Decompose a region of space into clusters based on the euclidean distance between points, and the normal angular deviation : assumes normalized point normals ! | |
| void | extractEuclideanClusters (const sensor_msgs::PointCloud &points, double tolerance, std::vector< std::vector< int > > &clusters, int nx_idx, int ny_idx, int nz_idx, double eps_angle, unsigned int min_pts_per_cluster) |
| Decompose a region of space into clusters based on the euclidean distance between points, and the normal angular deviation : assumes normalized point normals ! | |
| void | filterJumpEdges (const sensor_msgs::PointCloud &points, sensor_msgs::PointCloud &points_filtered, int k, int width, int height, double min_angle, double max_angle, const geometry_msgs::Point32 &viewpoint) |
| Filter jump edges in an organized point cloud dataset (e.g., acquired using TOF or dense stereo, etc) | |
| double | getAngleWithViewpoint (float px, float py, float pz, float qx, float qy, float qz, float vp_x=0, float vp_y=0, float vp_z=0) |
| Computes the angle between the lines created from 2 points and the viewpoint: [vp->p1], [p1->p2] Returns the angle (in degrees). | |
| bool | isBoundaryPoint (const sensor_msgs::PointCloud &points, int q_idx, const std::vector< int > &neighbors, const Eigen::Vector3d &u, const Eigen::Vector3d &v, double angle_threshold) |
| Check whether a point is a boundary point in a planar patch of projected points given by indices. | |
| void cloud_geometry::nearest::computeCentroid | ( | const sensor_msgs::PointCloud & | points, |
| geometry_msgs::Point32 & | centroid | ||
| ) | [inline] |
| void cloud_geometry::nearest::computeCentroid | ( | const geometry_msgs::Polygon & | poly, |
| geometry_msgs::Point32 & | centroid | ||
| ) | [inline] |
| void cloud_geometry::nearest::computeCentroid | ( | const sensor_msgs::PointCloud & | points, |
| const std::vector< int > & | indices, | ||
| sensor_msgs::PointCloud & | centroid | ||
| ) |
Compute the centroid of a set of points using their indices and return it as a PointCloud message with 1 value.
| points | the input point cloud |
| indices | the point cloud indices that need to be used |
| centroid | the output centroid |
Definition at line 92 of file nearest.cpp.
| void cloud_geometry::nearest::computeCentroid | ( | const sensor_msgs::PointCloud & | points, |
| const std::vector< int > & | indices, | ||
| geometry_msgs::Point32 & | centroid | ||
| ) | [inline] |
| void cloud_geometry::nearest::computeCentroid | ( | const sensor_msgs::PointCloudConstPtr & | points, |
| const std::vector< int > & | indices, | ||
| geometry_msgs::Point32 & | centroid | ||
| ) | [inline] |
| void cloud_geometry::nearest::computeCentroid | ( | const sensor_msgs::PointCloud & | points, |
| const std::vector< int > & | indices, | ||
| std::vector< double > & | centroid | ||
| ) | [inline] |
| void cloud_geometry::nearest::computeCentroid | ( | const sensor_msgs::PointCloud & | points, |
| sensor_msgs::PointCloud & | centroid | ||
| ) |
Compute the centroid of a set of points and return it as a PointCloud message with 1 value.
| points | the input point cloud |
| centroid | the output centroid |
Definition at line 55 of file nearest.cpp.
| void cloud_geometry::nearest::computeCentroid | ( | const sensor_msgs::PointCloud & | points, |
| std::vector< int > & | indices, | ||
| sensor_msgs::PointCloud & | centroid | ||
| ) |
| void cloud_geometry::nearest::computeCovarianceMatrix | ( | const sensor_msgs::PointCloud & | points, |
| Eigen::Matrix3d & | covariance_matrix, | ||
| geometry_msgs::Point32 & | centroid | ||
| ) | [inline] |
Compute the 3x3 covariance matrix of a given set of points. The result is returned as a Eigen::Matrix3d.
| points | the input point cloud |
| covariance_matrix | the 3x3 covariance matrix |
| centroid | the computed centroid |
| void cloud_geometry::nearest::computeCovarianceMatrix | ( | const sensor_msgs::PointCloud & | points, |
| Eigen::Matrix3d & | covariance_matrix | ||
| ) | [inline] |
| void cloud_geometry::nearest::computeCovarianceMatrix | ( | const sensor_msgs::PointCloud & | points, |
| const std::vector< int > & | indices, | ||
| Eigen::Matrix3d & | covariance_matrix, | ||
| geometry_msgs::Point32 & | centroid | ||
| ) | [inline] |
Compute the 3x3 covariance matrix of a given set of points using their indices. The result is returned as a Eigen::Matrix3d.
| points | the input point cloud |
| indices | the point cloud indices that need to be used |
| covariance_matrix | the 3x3 covariance matrix |
| centroid | the computed centroid |
| void cloud_geometry::nearest::computeCovarianceMatrix | ( | const sensor_msgs::PointCloudConstPtr & | points, |
| const std::vector< int > & | indices, | ||
| Eigen::Matrix3d & | covariance_matrix, | ||
| geometry_msgs::Point32 & | centroid | ||
| ) | [inline] |
Compute the 3x3 covariance matrix of a given set of points using their indices. The result is returned as a Eigen::Matrix3d.
| points | the input point cloud |
| indices | the point cloud indices that need to be used |
| covariance_matrix | the 3x3 covariance matrix |
| centroid | the computed centroid |
| void cloud_geometry::nearest::computeCovarianceMatrix | ( | const sensor_msgs::PointCloud & | points, |
| const std::vector< int > & | indices, | ||
| Eigen::Matrix3d & | covariance_matrix | ||
| ) | [inline] |
Compute the 3x3 covariance matrix of a given set of points using their indices. The result is returned as a Eigen::Matrix3d.
| points | the input point cloud |
| indices | the point cloud indices that need to be used |
| covariance_matrix | the 3x3 covariance matrix |
| void cloud_geometry::nearest::computeMomentInvariants | ( | const sensor_msgs::PointCloud & | points, |
| double & | j1, | ||
| double & | j2, | ||
| double & | j3 | ||
| ) |
Compute the 3 moment invariants (j1, j2, j3) for a given set of points.
| points | the input point cloud |
| j1 | the first moment invariant |
| j2 | the second moment invariant |
| j3 | the third moment invariant |
Definition at line 352 of file nearest.cpp.
| void cloud_geometry::nearest::computeMomentInvariants | ( | const sensor_msgs::PointCloud & | points, |
| const std::vector< int > & | indices, | ||
| double & | j1, | ||
| double & | j2, | ||
| double & | j3 | ||
| ) |
Compute the 3 moment invariants (j1, j2, j3) for a given set of points, using their indices.
| points | the input point cloud |
| indices | the point cloud indices that need to be used |
| j1 | the first moment invariant |
| j2 | the second moment invariant |
| j3 | the third moment invariant |
Definition at line 389 of file nearest.cpp.
| void cloud_geometry::nearest::computeOrganizedPointCloudNormals | ( | sensor_msgs::PointCloud & | points, |
| const sensor_msgs::PointCloud & | surface, | ||
| int | k, | ||
| int | downsample_factor, | ||
| int | width, | ||
| int | height, | ||
| double | max_z, | ||
| const geometry_msgs::Point32 & | viewpoint | ||
| ) |
Estimate the point normals and surface curvatures for a given organized point cloud dataset (points) using the data from a different point cloud (surface) for least-squares planar estimation.
| points | the input point cloud (on output, 4 extra channels will be added: nx, ny, nz, and curvatures) |
| surface | the point cloud data to use for least-squares planar estimation |
| k | the windowing factor (i.e., how many pixels in the depth image in all directions should the neighborhood of a point contain) |
| downsample_factor | factor for downsampling the input data, i.e., take every Nth row and column in the depth image |
| width | the width in pixels of the depth image |
| height | the height in pixels of the depth image |
| max_z | maximum distance threshold (on Z) between the query point and its neighbors (set to -1 to ignore the check) |
| viewpoint | the viewpoint where the cloud was acquired from (used for normal flip) |
Definition at line 676 of file nearest.cpp.
| void cloud_geometry::nearest::computeOrganizedPointCloudNormals | ( | sensor_msgs::PointCloud & | points, |
| const sensor_msgs::PointCloudConstPtr & | surface, | ||
| int | k, | ||
| int | downsample_factor, | ||
| int | width, | ||
| int | height, | ||
| double | max_z, | ||
| const geometry_msgs::Point32 & | viewpoint | ||
| ) |
Estimate the point normals and surface curvatures for a given organized point cloud dataset (points) using the data from a different point cloud (surface) for least-squares planar estimation.
| points | the input point cloud (on output, 4 extra channels will be added: nx, ny, nz, and curvatures) |
| surface | the point cloud data to use for least-squares planar estimation |
| k | the windowing factor (i.e., how many pixels in the depth image in all directions should the neighborhood of a point contain) |
| downsample_factor | factor for downsampling the input data, i.e., take every Nth row and column in the depth image |
| width | the width in pixels of the depth image |
| height | the height in pixels of the depth image |
| max_z | maximum distance threshold (on Z) between the query point and its neighbors (set to -1 to ignore the check) |
| viewpoint | the viewpoint where the cloud was acquired from (used for normal flip) |
Definition at line 773 of file nearest.cpp.
| void cloud_geometry::nearest::computeOrganizedPointCloudNormalsWithFiltering | ( | sensor_msgs::PointCloud & | points, |
| const sensor_msgs::PointCloud & | surface, | ||
| int | k, | ||
| int | downsample_factor, | ||
| int | width, | ||
| int | height, | ||
| double | max_z, | ||
| double | min_angle, | ||
| double | max_angle, | ||
| const geometry_msgs::Point32 & | viewpoint | ||
| ) |
Estimate the point normals and surface curvatures for a given organized point cloud dataset (points) using the data from a different point cloud (surface) for least-squares planar estimation.
| points | the input point cloud (on output, 4 extra channels will be added: nx, ny, nz, and curvatures) |
| surface | the point cloud data to use for least-squares planar estimation |
| k | the windowing factor (i.e., how many pixels in the depth image in all directions should the neighborhood of a point contain) |
| downsample_factor | factor for downsampling the input data, i.e., take every Nth row and column in the depth image |
| width | the width in pixels of the depth image |
| height | the height in pixels of the depth image |
| max_z | maximum distance threshold (on Z) between the query point and its neighbors (set to -1 to ignore the check) |
| min_angle | the minimum angle allowed between the viewpoint ray and the line formed by two subsequent points(used for filtering jump edge data) |
| max_angle | the maximum angle allowed between the viewpoint ray and the line formed by two subsequent points(used for filtering jump edge data) |
| viewpoint | the viewpoint where the cloud was acquired from (used for normal flip) |
Definition at line 872 of file nearest.cpp.
| void cloud_geometry::nearest::computePatchEigen | ( | const sensor_msgs::PointCloud & | points, |
| Eigen::Matrix3d & | eigen_vectors, | ||
| Eigen::Vector3d & | eigen_values | ||
| ) |
Compute the eigenvalues and eigenvectors of a given surface patch.
| points | the input point cloud |
| eigen_vectors | the resultant eigenvectors |
| eigen_values | the resultant eigenvalues |
Definition at line 129 of file nearest.cpp.
| void cloud_geometry::nearest::computePatchEigen | ( | const sensor_msgs::PointCloud & | points, |
| const std::vector< int > & | indices, | ||
| Eigen::Matrix3d & | eigen_vectors, | ||
| Eigen::Vector3d & | eigen_values | ||
| ) |
Compute the eigenvalues and eigenvectors of a given surface patch.
| points | the input point cloud |
| indices | the point cloud indices that need to be used |
| eigen_vectors | the resultant eigenvectors |
| eigen_values | the resultant eigenvalues |
Definition at line 150 of file nearest.cpp.
| void cloud_geometry::nearest::computePatchEigenNormalized | ( | const sensor_msgs::PointCloud & | points, |
| Eigen::Matrix3d & | eigen_vectors, | ||
| Eigen::Vector3d & | eigen_values, | ||
| geometry_msgs::Point32 & | centroid | ||
| ) |
Compute the eigenvalues and eigenvectors of a given surface patch from its normalized covariance matrix.
| points | the input point cloud |
| eigen_vectors | the resultant eigenvectors |
| eigen_values | the resultant eigenvalues |
| centroid | the centroid of the points |
Definition at line 171 of file nearest.cpp.
| void cloud_geometry::nearest::computePatchEigenNormalized | ( | const sensor_msgs::PointCloud & | points, |
| const std::vector< int > & | indices, | ||
| Eigen::Matrix3d & | eigen_vectors, | ||
| Eigen::Vector3d & | eigen_values, | ||
| geometry_msgs::Point32 & | centroid | ||
| ) |
Compute the eigenvalues and eigenvectors of a given surface patch from its normalized covariance matrix.
| points | the input point cloud |
| indices | the point cloud indices that need to be used |
| eigen_vectors | the resultant eigenvectors |
| eigen_values | the resultant eigenvalues |
| centroid | the centroid of the points |
Definition at line 202 of file nearest.cpp.
| void cloud_geometry::nearest::computePointCloudNormals | ( | sensor_msgs::PointCloud & | points, |
| const sensor_msgs::PointCloud & | surface, | ||
| int | k, | ||
| const geometry_msgs::PointStamped & | viewpoint | ||
| ) |
Estimate (in place) the point normals and surface curvatures for a given point cloud dataset (points) using the data from a different point cloud (surface) for least-squares planar estimation.
| points | the input point cloud (on output, 4 extra channels will be added: nx, ny, nz, and curvatures) |
| surface | the point cloud data to use for least-squares planar estimation |
| k | use a fixed number of k-nearest neighbors for the least-squares fit |
| viewpoint | the viewpoint where the cloud was acquired from (used for normal flip) |
Definition at line 480 of file nearest.cpp.
| void cloud_geometry::nearest::computePointCloudNormals | ( | sensor_msgs::PointCloud & | points, |
| const sensor_msgs::PointCloud & | surface, | ||
| double | radius, | ||
| const geometry_msgs::PointStamped & | viewpoint | ||
| ) |
Estimate (in place) the point normals and surface curvatures for a given point cloud dataset (points) using the data from a different point cloud (surface) for least-squares planar estimation.
| points | the input point cloud (on output, 4 extra channels will be added: nx, ny, nz, and curvatures) |
| surface | the point cloud data to use for least-squares planar estimation |
| radius | use a neighbor fixed radius search for the least-squares fit |
| viewpoint | the viewpoint where the cloud was acquired from (used for normal flip) |
Definition at line 525 of file nearest.cpp.
| void cloud_geometry::nearest::computePointCloudNormals | ( | sensor_msgs::PointCloud & | points, |
| int | k, | ||
| const geometry_msgs::PointStamped & | viewpoint | ||
| ) |
Estimate (in place) the point normals and surface curvatures for a given point cloud dataset (points)
| points | the input point cloud (on output, 4 extra channels will be added: nx, ny, nz, and curvatures) |
| k | use a fixed number of k-nearest neighbors for the least-squares fit |
| viewpoint | the viewpoint where the cloud was acquired from (used for normal flip) |
Definition at line 568 of file nearest.cpp.
| void cloud_geometry::nearest::computePointCloudNormals | ( | sensor_msgs::PointCloud & | points, |
| double | radius, | ||
| const geometry_msgs::PointStamped & | viewpoint | ||
| ) |
Estimate (in place) the point normals and surface curvatures for a given point cloud dataset (points)
| points | the input point cloud (on output, 4 extra channels will be added: nx, ny, nz, and curvatures) |
| radius | use a neighbor fixed radius search for the least-squares fit |
| viewpoint | the viewpoint where the cloud was acquired from (used for normal flip) |
Definition at line 623 of file nearest.cpp.
| void cloud_geometry::nearest::computePointNormal | ( | const sensor_msgs::PointCloud & | points, |
| Eigen::Vector4d & | plane_parameters, | ||
| double & | curvature | ||
| ) |
Compute the Least-Squares plane fit for a given set of points, and return the estimated plane parameters together with the surface curvature.
| points | the input point cloud |
| plane_parameters | the plane parameters as: a, b, c, d (ax + by + cz + d = 0) |
| curvature | the estimated surface curvature as a measure of
|
Definition at line 236 of file nearest.cpp.
| void cloud_geometry::nearest::computePointNormal | ( | const sensor_msgs::PointCloud & | points, |
| const std::vector< int > & | indices, | ||
| Eigen::Vector4d & | plane_parameters, | ||
| double & | curvature | ||
| ) |
Compute the Least-Squares plane fit for a given set of points, using their indices, and return the estimated plane parameters together with the surface curvature.
| points | the input point cloud |
| indices | the point cloud indices that need to be used |
| plane_parameters | the plane parameters as: a, b, c, d (ax + by + cz + d = 0) |
| curvature | the estimated surface curvature as a measure of
|
Definition at line 275 of file nearest.cpp.
| void cloud_geometry::nearest::computePointNormal | ( | const sensor_msgs::PointCloudConstPtr & | points, |
| const std::vector< int > & | indices, | ||
| Eigen::Vector4d & | plane_parameters, | ||
| double & | curvature | ||
| ) |
Compute the Least-Squares plane fit for a given set of points, using their indices, and return the estimated plane parameters together with the surface curvature.
| points | the input point cloud |
| indices | the point cloud indices that need to be used |
| plane_parameters | the plane parameters as: a, b, c, d (ax + by + cz + d = 0) |
| curvature | the estimated surface curvature as a measure of
|
Definition at line 315 of file nearest.cpp.
| void cloud_geometry::nearest::extractEuclideanClusters | ( | const sensor_msgs::PointCloud & | points, |
| const std::vector< int > & | indices, | ||
| double | tolerance, | ||
| std::vector< std::vector< int > > & | clusters, | ||
| int | nx_idx, | ||
| int | ny_idx, | ||
| int | nz_idx, | ||
| double | eps_angle, | ||
| unsigned int | min_pts_per_cluster | ||
| ) |
Decompose a region of space into clusters based on the euclidean distance between points, and the normal angular deviation : assumes normalized point normals !
| points | the point cloud message |
| indices | a list of point indices to use |
| tolerance | the spatial tolerance as a measure in the L2 Euclidean space |
| clusters | the resultant clusters containing point indices |
| nx_idx | the index of the channel containing the X component of the normal (use -1 to disable the check) |
| ny_idx | the index of the channel containing the Y component of the normal (use -1 to disable the check) |
| nz_idx | the index of the channel containing the Z component of the normal (use -1 to disable the check) |
| eps_angle | the maximum allowed difference between normals in degrees for cluster/region growing (only valid if nx_idx && ny_idx && nz_idx != -1) |
| min_pts_per_cluster | minimum number of points that a cluster may contain (default = 1) |
Definition at line 1055 of file nearest.cpp.
| void cloud_geometry::nearest::extractEuclideanClusters | ( | const sensor_msgs::PointCloud & | points, |
| double | tolerance, | ||
| std::vector< std::vector< int > > & | clusters, | ||
| int | nx_idx, | ||
| int | ny_idx, | ||
| int | nz_idx, | ||
| double | eps_angle, | ||
| unsigned int | min_pts_per_cluster | ||
| ) |
Decompose a region of space into clusters based on the euclidean distance between points, and the normal angular deviation : assumes normalized point normals !
| points | the point cloud message |
| tolerance | the spatial tolerance as a measure in the L2 Euclidean space |
| clusters | the resultant clusters containing point indices |
| nx_idx | the index of the channel containing the X component of the normal (use -1 to disable the check) |
| ny_idx | the index of the channel containing the Y component of the normal (use -1 to disable the check) |
| nz_idx | the index of the channel containing the Z component of the normal (use -1 to disable the check) |
| eps_angle | the maximum allowed difference between normals in degrees for cluster/region growing (only valid if nx_idx && ny_idx && nz_idx != -1) |
| min_pts_per_cluster | minimum number of points that a cluster may contain (default = 1) |
Definition at line 1149 of file nearest.cpp.
| void cloud_geometry::nearest::filterJumpEdges | ( | const sensor_msgs::PointCloud & | points, |
| sensor_msgs::PointCloud & | points_filtered, | ||
| int | k, | ||
| int | width, | ||
| int | height, | ||
| double | min_angle, | ||
| double | max_angle, | ||
| const geometry_msgs::Point32 & | viewpoint | ||
| ) |
Filter jump edges in an organized point cloud dataset (e.g., acquired using TOF or dense stereo, etc)
the input point cloud size is assumed to have (width*height) number of points, in order!
| points | the input organized point cloud data |
| points_filtered | the output filtered point cloud data |
| k | the windowing factor (i.e., how many pixels in the depth image in all directions should the neighborhood of a point contain) |
| width | the width in pixels of the depth image |
| height | the height in pixels of the depth image |
| min_angle | the minimum angle allowed between the viewpoint ray and the line formed by two subsequent points(used for filtering jump edge data) |
| max_angle | the maximum angle allowed between the viewpoint ray and the line formed by two subsequent points(used for filtering jump edge data) |
| viewpoint | the viewpoint where the cloud was acquired from (used for normal flip) |
Definition at line 975 of file nearest.cpp.
| double cloud_geometry::nearest::getAngleWithViewpoint | ( | float | px, |
| float | py, | ||
| float | pz, | ||
| float | qx, | ||
| float | qy, | ||
| float | qz, | ||
| float | vp_x = 0, |
||
| float | vp_y = 0, |
||
| float | vp_z = 0 |
||
| ) | [inline] |
Computes the angle between the lines created from 2 points and the viewpoint: [vp->p1], [p1->p2] Returns the angle (in degrees).
| px | X coordinate for the first point |
| py | Y coordinate for the first point |
| pz | Z coordinate for the first point |
| qx | X coordinate for the second point |
| qy | Y coordinate for the second point |
| qz | Z coordinate for the second point |
| vp_x | X coordinate of the viewpoint (0 by default) |
| vp_y | Y coordinate of the viewpoint (0 by default) |
| vp_z | Z coordinate of the viewpoint (0 by default) |
| bool cloud_geometry::nearest::isBoundaryPoint | ( | const sensor_msgs::PointCloud & | points, |
| int | q_idx, | ||
| const std::vector< int > & | neighbors, | ||
| const Eigen::Vector3d & | u, | ||
| const Eigen::Vector3d & | v, | ||
| double | angle_threshold | ||
| ) |
Check whether a point is a boundary point in a planar patch of projected points given by indices.
| points | a pointer to the input point cloud |
| q_idx | the index of the query point in points |
| neighbors | the estimated point neighbors of the query point |
| u | the u direction |
| v | the v direction |
| angle_threshold | the threshold angle (default $ / 2.0$) |
Definition at line 428 of file nearest.cpp.