#include <plane_extraction.h>
| Public Types | |
| typedef pcl::PointXYZRGB | Point | 
| typedef pcl::PointXYZRGB | Point | 
| Public Member Functions | |
| void | extractPlanes (const pcl::PointCloud< Point >::ConstPtr &pc_in, std::vector< pcl::PointCloud< Point >, Eigen::aligned_allocator< pcl::PointCloud< Point > > > &v_cloud_hull, std::vector< std::vector< pcl::Vertices > > &v_hull_polygons, std::vector< pcl::ModelCoefficients > &v_coefficients_plane) | 
| void | extractPlanes (const pcl::PointCloud< Point >::ConstPtr &pc_in, std::vector< pcl::PointCloud< Point >, Eigen::aligned_allocator< pcl::PointCloud< Point > > > &v_cloud_hull, std::vector< std::vector< pcl::Vertices > > &v_hull_polygons, std::vector< pcl::ModelCoefficients > &v_coefficients_plane) | 
| void | findClosestTable (std::vector< pcl::PointCloud< Point >, Eigen::aligned_allocator< pcl::PointCloud< Point > > > &v_cloud_hull, std::vector< pcl::ModelCoefficients > &v_coefficients_plane, Eigen::Vector3f &robot_pose, unsigned int &idx) | 
| void | findClosestTable (std::vector< pcl::PointCloud< Point >, Eigen::aligned_allocator< pcl::PointCloud< Point > > > &v_cloud_hull, std::vector< pcl::ModelCoefficients > &v_coefficients_plane, Eigen::Vector3f &robot_pose, unsigned int &idx) | 
| PlaneExtraction () | |
| PlaneExtraction () | |
| void | saveHulls (pcl::PointCloud< Point > &cloud_hull, std::vector< pcl::Vertices > &hull_polygons, int plane_ctr) | 
| void | saveHulls (pcl::PointCloud< Point > &cloud_hull, std::vector< pcl::Vertices > &hull_polygons, int plane_ctr) | 
| void | setAlpha (double alpha) | 
| void | setAlpha (double alpha) | 
| void | setClusterTolerance (double cluster_tolerance) | 
| void | setClusterTolerance (double cluster_tolerance) | 
| void | setFilePath (std::string file_path) | 
| void | setFilePath (std::string file_path) | 
| void | setMinPlaneSize (unsigned int min_plane_size) | 
| void | setMinPlaneSize (unsigned int min_plane_size) | 
| void | setPlaneConstraint (PlaneConstraint constr) | 
| void | setPlaneConstraint (PlaneConstraint constr) | 
| void | setSaveToFile (bool save_to_file) | 
| void | setSaveToFile (bool save_to_file) | 
| void | setSegmentationParamDistanceThreshold (double threshold) | 
| void | setSegmentationParamDistanceThreshold (double threshold) | 
| void | setSegmentationParamMaxIterations (int max_iterations) | 
| void | setSegmentationParamMaxIterations (int max_iterations) | 
| void | setSegmentationParamMethodType (int method_type) | 
| void | setSegmentationParamMethodType (int method_type) | 
| void | setSegmentationParamOptimizeCoefficients (bool optimize_coefficients) | 
| void | setSegmentationParamOptimizeCoefficients (bool optimize_coefficients) | 
| ~PlaneExtraction () | |
| ~PlaneExtraction () | |
| Public Attributes | |
| std::vector< std::vector< int > > | extracted_planes_indices_ | 
| Protected Member Functions | |
| void | dumpToPCDFileAllPlanes (pcl::PointCloud< Point >::Ptr dominant_plane_ptr) | 
| write point cloud data to a file | |
| void | dumpToPCDFileAllPlanes (pcl::PointCloud< Point >::Ptr dominant_plane_ptr) | 
| write point cloud data to a file | |
| bool | isValidPlane (const pcl::ModelCoefficients &coefficients_plane) | 
| check whether given plane is valid or not | |
| bool | isValidPlane (const pcl::ModelCoefficients &coefficients_plane) | 
| check whether given plane is valid or not | |
| Protected Attributes | |
| double | alpha_ | 
| pcl::ConcaveHull< Point > | chull_ | 
| pcl::EuclideanClusterExtraction < Point > | cluster_ | 
| pcl::EuclideanClusterExtraction < Point > | cluster_plane_ | 
| double | cluster_tolerance_ | 
| int | ctr_ | 
| double | distance_threshold_ | 
| pcl::ExtractIndices< Point > | extract_ | 
| pcl::PointCloud< Point > | extracted_planes_ | 
| std::string | file_path_ | 
| int | max_iterations_ | 
| unsigned int | min_plane_size_ | 
| PlaneConstraint | plane_constraint_ | 
| pcl::ProjectInliers< Point > | proj_ | 
| double | radius_ | 
| bool | save_to_file_ | 
| pcl::SACSegmentation< Point > | seg_ | 
Definition at line 85 of file plane_extraction/plane_extraction.h.
| typedef pcl::PointXYZRGB PlaneExtraction::Point | 
Definition at line 88 of file plane_extraction/plane_extraction.h.
| typedef pcl::PointXYZRGB PlaneExtraction::Point | 
Definition at line 96 of file plane_extraction.h.
Definition at line 94 of file plane_extraction.cpp.
| PlaneExtraction::~PlaneExtraction | ( | ) |  [inline] | 
void
Definition at line 93 of file plane_extraction/plane_extraction.h.
| PlaneExtraction::~PlaneExtraction | ( | ) |  [inline] | 
void
Definition at line 101 of file plane_extraction.h.
| void PlaneExtraction::dumpToPCDFileAllPlanes | ( | pcl::PointCloud< Point >::Ptr | dominant_plane_ptr | ) |  [protected] | 
write point cloud data to a file
| dominant_plane_ptr | pointer to point cloud specifying dominant plane | 
Definition at line 440 of file plane_extraction.cpp.
| void PlaneExtraction::dumpToPCDFileAllPlanes | ( | pcl::PointCloud< Point >::Ptr | dominant_plane_ptr | ) |  [protected] | 
write point cloud data to a file
| dominant_plane_ptr | pointer to point cloud specifying dominant plane | 
| void PlaneExtraction::extractPlanes | ( | const pcl::PointCloud< Point >::ConstPtr & | pc_in, | 
| std::vector< pcl::PointCloud< Point >, Eigen::aligned_allocator< pcl::PointCloud< Point > > > & | v_cloud_hull, | ||
| std::vector< std::vector< pcl::Vertices > > & | v_hull_polygons, | ||
| std::vector< pcl::ModelCoefficients > & | v_coefficients_plane | ||
| ) | 
Definition at line 182 of file plane_extraction.cpp.
| void PlaneExtraction::extractPlanes | ( | const pcl::PointCloud< Point >::ConstPtr & | pc_in, | 
| std::vector< pcl::PointCloud< Point >, Eigen::aligned_allocator< pcl::PointCloud< Point > > > & | v_cloud_hull, | ||
| std::vector< std::vector< pcl::Vertices > > & | v_hull_polygons, | ||
| std::vector< pcl::ModelCoefficients > & | v_coefficients_plane | ||
| ) | 
| void PlaneExtraction::findClosestTable | ( | std::vector< pcl::PointCloud< Point >, Eigen::aligned_allocator< pcl::PointCloud< Point > > > & | v_cloud_hull, | 
| std::vector< pcl::ModelCoefficients > & | v_coefficients_plane, | ||
| Eigen::Vector3f & | robot_pose, | ||
| unsigned int & | idx | ||
| ) | 
Definition at line 476 of file plane_extraction.cpp.
| void PlaneExtraction::findClosestTable | ( | std::vector< pcl::PointCloud< Point >, Eigen::aligned_allocator< pcl::PointCloud< Point > > > & | v_cloud_hull, | 
| std::vector< pcl::ModelCoefficients > & | v_coefficients_plane, | ||
| Eigen::Vector3f & | robot_pose, | ||
| unsigned int & | idx | ||
| ) | 
| bool PlaneExtraction::isValidPlane | ( | const pcl::ModelCoefficients & | coefficients_plane | ) |  [protected] | 
check whether given plane is valid or not
| coefficients_plane | pointer to coefficients of the plane to be evaluated | 
Definition at line 145 of file plane_extraction.cpp.
| bool PlaneExtraction::isValidPlane | ( | const pcl::ModelCoefficients & | coefficients_plane | ) |  [protected] | 
check whether given plane is valid or not
| coefficients_plane | pointer to coefficients of the plane to be evaluated | 
| void PlaneExtraction::saveHulls | ( | pcl::PointCloud< Point > & | cloud_hull, | 
| std::vector< pcl::Vertices > & | hull_polygons, | ||
| int | plane_ctr | ||
| ) | 
Definition at line 455 of file plane_extraction.cpp.
| void PlaneExtraction::saveHulls | ( | pcl::PointCloud< Point > & | cloud_hull, | 
| std::vector< pcl::Vertices > & | hull_polygons, | ||
| int | plane_ctr | ||
| ) | 
| void PlaneExtraction::setAlpha | ( | double | alpha | ) |  [inline] | 
Definition at line 180 of file plane_extraction/plane_extraction.h.
| void PlaneExtraction::setAlpha | ( | double | alpha | ) |  [inline] | 
Definition at line 188 of file plane_extraction.h.
| void PlaneExtraction::setClusterTolerance | ( | double | cluster_tolerance | ) |  [inline] | 
Definition at line 128 of file plane_extraction/plane_extraction.h.
| void PlaneExtraction::setClusterTolerance | ( | double | cluster_tolerance | ) |  [inline] | 
Definition at line 136 of file plane_extraction.h.
| void PlaneExtraction::setFilePath | ( | std::string | file_path | ) |  [inline] | 
Definition at line 116 of file plane_extraction/plane_extraction.h.
| void PlaneExtraction::setFilePath | ( | std::string | file_path | ) |  [inline] | 
Definition at line 124 of file plane_extraction.h.
| void PlaneExtraction::setMinPlaneSize | ( | unsigned int | min_plane_size | ) |  [inline] | 
Definition at line 136 of file plane_extraction/plane_extraction.h.
| void PlaneExtraction::setMinPlaneSize | ( | unsigned int | min_plane_size | ) |  [inline] | 
Definition at line 144 of file plane_extraction.h.
| void PlaneExtraction::setPlaneConstraint | ( | PlaneConstraint | constr | ) |  [inline] | 
Definition at line 110 of file plane_extraction/plane_extraction.h.
| void PlaneExtraction::setPlaneConstraint | ( | PlaneConstraint | constr | ) |  [inline] | 
Definition at line 118 of file plane_extraction.h.
| void PlaneExtraction::setSaveToFile | ( | bool | save_to_file | ) |  [inline] | 
Definition at line 122 of file plane_extraction/plane_extraction.h.
| void PlaneExtraction::setSaveToFile | ( | bool | save_to_file | ) |  [inline] | 
Definition at line 130 of file plane_extraction.h.
| void PlaneExtraction::setSegmentationParamDistanceThreshold | ( | double | threshold | ) |  [inline] | 
Definition at line 174 of file plane_extraction/plane_extraction.h.
| void PlaneExtraction::setSegmentationParamDistanceThreshold | ( | double | threshold | ) |  [inline] | 
Definition at line 182 of file plane_extraction.h.
| void PlaneExtraction::setSegmentationParamMaxIterations | ( | int | max_iterations | ) |  [inline] | 
Definition at line 168 of file plane_extraction/plane_extraction.h.
| void PlaneExtraction::setSegmentationParamMaxIterations | ( | int | max_iterations | ) |  [inline] | 
Definition at line 176 of file plane_extraction.h.
| void PlaneExtraction::setSegmentationParamMethodType | ( | int | method_type | ) |  [inline] | 
Definition at line 156 of file plane_extraction/plane_extraction.h.
| void PlaneExtraction::setSegmentationParamMethodType | ( | int | method_type | ) |  [inline] | 
Definition at line 164 of file plane_extraction.h.
| void PlaneExtraction::setSegmentationParamOptimizeCoefficients | ( | bool | optimize_coefficients | ) |  [inline] | 
Definition at line 150 of file plane_extraction/plane_extraction.h.
| void PlaneExtraction::setSegmentationParamOptimizeCoefficients | ( | bool | optimize_coefficients | ) |  [inline] | 
Definition at line 158 of file plane_extraction.h.
| double PlaneExtraction::alpha_  [protected] | 
Definition at line 232 of file plane_extraction/plane_extraction.h.
| pcl::ConcaveHull< Point > PlaneExtraction::chull_  [protected] | 
Definition at line 241 of file plane_extraction/plane_extraction.h.
| pcl::EuclideanClusterExtraction< Point > PlaneExtraction::cluster_  [protected] | 
Definition at line 234 of file plane_extraction/plane_extraction.h.
| pcl::EuclideanClusterExtraction< Point > PlaneExtraction::cluster_plane_  [protected] | 
Definition at line 235 of file plane_extraction/plane_extraction.h.
| double PlaneExtraction::cluster_tolerance_  [protected] | 
Definition at line 220 of file plane_extraction/plane_extraction.h.
| int PlaneExtraction::ctr_  [protected] | 
Definition at line 214 of file plane_extraction/plane_extraction.h.
| double PlaneExtraction::distance_threshold_  [protected] | 
Definition at line 229 of file plane_extraction/plane_extraction.h.
| pcl::ExtractIndices< Point > PlaneExtraction::extract_  [protected] | 
Definition at line 238 of file plane_extraction/plane_extraction.h.
| pcl::PointCloud< Point > PlaneExtraction::extracted_planes_  [protected] | 
Definition at line 243 of file plane_extraction/plane_extraction.h.
| std::vector< std::vector< int > > PlaneExtraction::extracted_planes_indices_ | 
Definition at line 246 of file plane_extraction/plane_extraction.h.
| std::string PlaneExtraction::file_path_  [protected] | 
Definition at line 215 of file plane_extraction/plane_extraction.h.
| int PlaneExtraction::max_iterations_  [protected] | 
Definition at line 228 of file plane_extraction/plane_extraction.h.
| unsigned int PlaneExtraction::min_plane_size_  [protected] | 
Definition at line 221 of file plane_extraction/plane_extraction.h.
| PlaneConstraint PlaneExtraction::plane_constraint_  [protected] | 
Definition at line 217 of file plane_extraction/plane_extraction.h.
| pcl::ProjectInliers< Point > PlaneExtraction::proj_  [protected] | 
Definition at line 240 of file plane_extraction/plane_extraction.h.
| double PlaneExtraction::radius_  [protected] | 
Definition at line 224 of file plane_extraction/plane_extraction.h.
| bool PlaneExtraction::save_to_file_  [protected] | 
Definition at line 216 of file plane_extraction/plane_extraction.h.
| pcl::SACSegmentation< Point > PlaneExtraction::seg_  [protected] | 
Definition at line 237 of file plane_extraction/plane_extraction.h.