SurfaceFinder attempt to find multiple horizontal surfaces given a shelf scene. More...
#include <surface_finder.h>
Public Member Functions | |
void | ExploreSurfaces (std::vector< pcl::PointIndices::Ptr > *indices_vec, std::vector< pcl::ModelCoefficients > *coeffs_vec) |
Find the horizontal surfaces in a point cloud scene. | |
void | set_angle_tolerance_degree (double angle_tolerance_degree) |
Set the angle of the surface compare to horizontal surface. | |
void | set_cloud (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud) |
Set the input point cloud. | |
void | set_cloud_indices (const pcl::PointIndices::Ptr cloud_indices) |
Set the indices of the input point cloud. | |
void | set_max_point_distance (double max_point_distance) |
Set the maximum distance for a point to be considered part of surfaces. | |
void | set_max_surface_amount (int max_surface_amount) |
Set the maximum number of the surfaces in the output of ExploreSurfaces. | |
void | set_min_iteration (int min_iteration) |
Set the minimum number of iterations for the algorithm to find surfaces. | |
void | set_min_surface_amount (int min_surface_amount) |
Set the minimum number of surfaces in the output of ExploreSurfaces. | |
void | set_surface_point_threshold (int surface_point_threshold) |
Set the minimum amount of points contained by a surface candidate. | |
SurfaceFinder () | |
Default constructor. | |
Private Member Functions | |
void | FitSurface (const pcl::PointIndices::Ptr old_indices_ptr, const pcl::ModelCoefficients::Ptr old_coeff_ptr, pcl::PointIndices::Ptr new_indices_ptr, pcl::ModelCoefficients::Ptr new_coeff_ptr) |
void | SortIndices () |
Private Attributes | |
double | angle_tolerance_degree_ |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr | cloud_ |
pcl::PointIndices::Ptr | cloud_indices_ |
double | max_point_distance_ |
size_t | max_surface_amount_ |
size_t | min_iteration_ |
size_t | min_surface_amount_ |
std::map< double, std::vector < int > > | sorted_indices_ |
size_t | surface_point_threshold_ |
SurfaceFinder attempt to find multiple horizontal surfaces given a shelf scene.
This class is designed to find surfaces in a shelf scene such as a bookshelf. In particular, this class finds the horizontal surfaces if the following conditions are met: 1. No NaN points in the input cloud 2. Each target surface has different height
If the input cloud meets the requirement. Mutation functions of this class can be used to adjust the parameters based on the scenario of the point cloud scene.
Example usage:
SurfaceFinder finder; finder.set_cloud(pcl_cloud); finder.set_cloud_indices(point_indices); finder.set_angle_tolerance_degree(10); finder.set_max_point_distance(0.01); finder.set_min_iteration(1000); finder.set_surface_point_threshold(10000); std::vector<pcl::PointIndices::Ptr> indices; std::vector<pcl::ModelCoefficients> coeffs; finder.ExploreSurfaces(&indices, &coeffs);
Definition at line 40 of file surface_finder.h.
Default constructor.
Definition at line 140 of file surface_finder.cpp.
void surface_perception::SurfaceFinder::ExploreSurfaces | ( | std::vector< pcl::PointIndices::Ptr > * | indices_vec, |
std::vector< pcl::ModelCoefficients > * | coeffs_vec | ||
) |
Find the horizontal surfaces in a point cloud scene.
The algorithm attempts to surfaces in a point cloud scene and terminate if all of the following conditions are met: 1. The algorithm finds the minimum number of surface required. 2. The algorithm finishes the specified number of iteration.
Once the surfaces are found, the surface i has: 1. indices as indices_vec[i] 2. coefficients as coeffs_vec[i]
[out] | indices_vec | The indices for of each output surface. |
[out] | coeffs_vec | The coefficients of planes that represent each surface. |
Definition at line 206 of file surface_finder.cpp.
void surface_perception::SurfaceFinder::FitSurface | ( | const pcl::PointIndices::Ptr | old_indices_ptr, |
const pcl::ModelCoefficients::Ptr | old_coeff_ptr, | ||
pcl::PointIndices::Ptr | new_indices_ptr, | ||
pcl::ModelCoefficients::Ptr | new_coeff_ptr | ||
) | [private] |
Definition at line 384 of file surface_finder.cpp.
void surface_perception::SurfaceFinder::set_angle_tolerance_degree | ( | double | angle_tolerance_degree | ) |
Set the angle of the surface compare to horizontal surface.
Because the current state algorithm only search for horizontal surfaces, the angle set through this function is not used in surface detection.
[in] | angle_tolerance_degree | The maximum angle difference between a surface candidate against a horizontal surface. |
Definition at line 159 of file surface_finder.cpp.
void surface_perception::SurfaceFinder::set_cloud | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud | ) |
Set the input point cloud.
[in] | cloud | The input cloud for surface detection. NaN values in the input cloud should be removed before being passed to this function. |
Definition at line 151 of file surface_finder.cpp.
void surface_perception::SurfaceFinder::set_cloud_indices | ( | const pcl::PointIndices::Ptr | cloud_indices | ) |
Set the indices of the input point cloud.
[in] | cloud_indices | The indices of the input point cloud. |
Definition at line 153 of file surface_finder.cpp.
void surface_perception::SurfaceFinder::set_max_point_distance | ( | double | max_point_distance | ) |
Set the maximum distance for a point to be considered part of surfaces.
[in] | max_point_distance | The maximum distance between a point and a plane that represents the surface. |
Definition at line 163 of file surface_finder.cpp.
void surface_perception::SurfaceFinder::set_max_surface_amount | ( | int | max_surface_amount | ) |
Set the maximum number of the surfaces in the output of ExploreSurfaces.
[in] | max_surface_amount | The upper bound of the surface amount that can not be exceeded in the output of ExploreSurfaces. |
Definition at line 196 of file surface_finder.cpp.
void surface_perception::SurfaceFinder::set_min_iteration | ( | int | min_iteration | ) |
Set the minimum number of iterations for the algorithm to find surfaces.
The algorithm is designed to run at least the given number of iteration or finding the specified minimum number of surfaces in a given scene.
[in] | min_iteration | The minimum number of iteration required before the algorithm can stop search for surfaces. |
Definition at line 167 of file surface_finder.cpp.
void surface_perception::SurfaceFinder::set_min_surface_amount | ( | int | min_surface_amount | ) |
Set the minimum number of surfaces in the output of ExploreSurfaces.
[in] | min_surface_amount | The specified number of surfaces that must be in the output of ExploreSurfaces. |
Definition at line 186 of file surface_finder.cpp.
void surface_perception::SurfaceFinder::set_surface_point_threshold | ( | int | surface_point_threshold | ) |
Set the minimum amount of points contained by a surface candidate.
The amount of points for a surface is indicated by the number of points reside within the maximum distance of a plane. As the algorithm explores surfaces, the surface that have points less that required amount will be considered a candidate.
[in] | surface_point_threshold | The minimum number of points a surface candidate must have. |
Definition at line 176 of file surface_finder.cpp.
void surface_perception::SurfaceFinder::SortIndices | ( | ) | [private] |
Definition at line 366 of file surface_finder.cpp.
double surface_perception::SurfaceFinder::angle_tolerance_degree_ [private] |
Definition at line 127 of file surface_finder.h.
pcl::PointCloud<pcl::PointXYZRGB>::Ptr surface_perception::SurfaceFinder::cloud_ [private] |
Definition at line 125 of file surface_finder.h.
pcl::PointIndices::Ptr surface_perception::SurfaceFinder::cloud_indices_ [private] |
Definition at line 126 of file surface_finder.h.
double surface_perception::SurfaceFinder::max_point_distance_ [private] |
Definition at line 128 of file surface_finder.h.
size_t surface_perception::SurfaceFinder::max_surface_amount_ [private] |
Definition at line 132 of file surface_finder.h.
size_t surface_perception::SurfaceFinder::min_iteration_ [private] |
Definition at line 129 of file surface_finder.h.
size_t surface_perception::SurfaceFinder::min_surface_amount_ [private] |
Definition at line 131 of file surface_finder.h.
std::map<double, std::vector<int> > surface_perception::SurfaceFinder::sorted_indices_ [private] |
Definition at line 133 of file surface_finder.h.
size_t surface_perception::SurfaceFinder::surface_point_threshold_ [private] |
Definition at line 130 of file surface_finder.h.