#include "ros/ros.h"#include "pcl/console/parse.h"#include "pcl/io/pcd_io.h"#include "pcl/surface/convex_hull.h"#include "pcl/filters/voxel_grid.h"#include "pcl/filters/passthrough.h"#include "pcl/filters/extract_indices.h"#include "pcl/filters/project_inliers.h"#include "pcl/filters/statistical_outlier_removal.h"#include "pcl/sample_consensus/method_types.h"#include "pcl/sample_consensus/impl/ransac.hpp"#include "pcl/segmentation/sac_segmentation.h"#include "pcl/segmentation/extract_clusters.h"#include "pcl/segmentation/extract_polygonal_prism_data.h"#include "pcl/visualization/pcl_visualizer.h"#include "pcl_ias_sample_consensus/pcl_sac_model_orientation.h"#include "dos_pcl/segmentation/door_detection_by_color_and_fixture.h"
Go to the source code of this file.
| Typedefs | |
| typedef pcl::PointXYZ | PointT | 
| Functions | |
| bool | findBoxModel (boost::shared_ptr< const pcl::PointCloud< PointT > > cloud, pcl::PointCloud< pcl::Normal > nrmls, std::vector< double > &coeff, double eps_angle_=0.1, double success_probability_=0.99, int verbosity_level_=1) | 
| * | |
| void | getAxesOrientedSurfaces (pcl::PointCloud< PointT > &input_cloud, pcl::PointCloud< pcl::Normal > &normals_cloud, Eigen::Vector3f axis, double epsilon_angle, double plane_threshold, int minimum_plane_inliers, int maximum_plane_iterations, int minimum_size_of_plane_cluster, double plane_inliers_clustering_tolerance, std::vector< pcl::PointCloud< PointT >::Ptr > &planar_surfaces, std::vector< std::string > &planar_surfaces_ids, std::vector< pcl::PointIndices::Ptr > &planar_surfaces_indices, std::vector< pcl::ModelCoefficients::Ptr > &planar_surfaces_coefficients, pcl::visualization::PCLVisualizer &viewer) | 
| void | getMinAndMax (boost::shared_ptr< const pcl::PointCloud< PointT > > cloud_, Eigen::VectorXf model_coefficients, boost::shared_ptr< pcl::SACModelOrientation< pcl::Normal > > model, std::vector< int > &min_max_indices, std::vector< float > &min_max_distances) | 
| * | |
| float | getRGB (float r, float g, float b) | 
| int | main (int argc, char **argv) | 
| Main routine of the method. Segmentation of point cloud data. | |
| Variables | |
| double | center_radius = 0.085 | 
| [meters] | |
| bool | clean = false | 
| double | cluster_tolerance = 0.020 | 
| [meters] | |
| double | color_radius = 0.050 | 
| double | epsilon_angle = 0.010 | 
| [percentage] | |
| bool | find_box_model = true | 
| double | fixture_cluster_tolerance = 0.025 | 
| [meters] | |
| int | fixture_min_pts_per_cluster = 150 | 
| [points] | |
| double | handle_clustering_tolerance = 0.050 | 
| [points] | |
| double | height_of_ceiling = 0.050 | 
| [percentage] | |
| double | height_of_floor = 0.025 | 
| double | height_of_walls = 0.750 | 
| [percentage] | |
| double | init_radius = 0.035 | 
| int | maximum_plane_iterations = 1000 | 
| [points] | |
| int | min_pts_per_cluster = 150 | 
| int | minimum_plane_inliers = 1000 | 
| [meters] | |
| int | minimum_size_of_handle_cluster = 25 | 
| [meters] | |
| int | minimum_size_of_plane_cluster = 100 | 
| [iterations] | |
| double | plane_inliers_clustering_tolerance = 0.100 | 
| [points] | |
| double | plane_threshold = 0.100 | 
| [radians] | |
| bool | segmentation_by_color_and_fixture = false | 
| int | size_of_points = 1 | 
| int | std_limit = 2 | 
| bool | step = false | 
| [points] | |
| bool | verbose = false | 
| typedef pcl::PointXYZ PointT | 
Definition at line 68 of file segmentation_of_pointcloud.cpp.
| bool findBoxModel | ( | boost::shared_ptr< const pcl::PointCloud< PointT > > | cloud, | 
| pcl::PointCloud< pcl::Normal > | nrmls, | ||
| std::vector< double > & | coeff, | ||
| double | eps_angle_ = 0.1, | ||
| double | success_probability_ = 0.99, | ||
| int | verbosity_level_ = 1 | ||
| ) | 
*
actual model fitting happens here
: inliers are actually indexes in the indices_ array, but that is not set (by default it has all the points in the correct order)
: making things transparent for the outside... not really needed
best_model_ contains actually the samples used to find the best model!
: making things transparent for the outside... not really needed
Definition at line 184 of file segmentation_of_pointcloud.cpp.
| void getAxesOrientedSurfaces | ( | pcl::PointCloud< PointT > & | input_cloud, | 
| pcl::PointCloud< pcl::Normal > & | normals_cloud, | ||
| Eigen::Vector3f | axis, | ||
| double | epsilon_angle, | ||
| double | plane_threshold, | ||
| int | minimum_plane_inliers, | ||
| int | maximum_plane_iterations, | ||
| int | minimum_size_of_plane_cluster, | ||
| double | plane_inliers_clustering_tolerance, | ||
| std::vector< pcl::PointCloud< PointT >::Ptr > & | planar_surfaces, | ||
| std::vector< std::string > & | planar_surfaces_ids, | ||
| std::vector< pcl::PointIndices::Ptr > & | planar_surfaces_indices, | ||
| std::vector< pcl::ModelCoefficients::Ptr > & | planar_surfaces_coefficients, | ||
| pcl::visualization::PCLVisualizer & | viewer | ||
| ) | 
*
Definition at line 391 of file segmentation_of_pointcloud.cpp.
| void getMinAndMax | ( | boost::shared_ptr< const pcl::PointCloud< PointT > > | cloud_, | 
| Eigen::VectorXf | model_coefficients, | ||
| boost::shared_ptr< pcl::SACModelOrientation< pcl::Normal > > | model, | ||
| std::vector< int > & | min_max_indices, | ||
| std::vector< float > & | min_max_distances | ||
| ) | 
*
Definition at line 134 of file segmentation_of_pointcloud.cpp.
| float getRGB | ( | float | r, | 
| float | g, | ||
| float | b | ||
| ) | 
Definition at line 125 of file segmentation_of_pointcloud.cpp.
| int main | ( | int | argc, | 
| char ** | argv | ||
| ) | 
Main routine of the method. Segmentation of point cloud data.
*
Definition at line 700 of file segmentation_of_pointcloud.cpp.
| double center_radius = 0.085 | 
[meters]
Definition at line 94 of file segmentation_of_pointcloud.cpp.
Definition at line 104 of file segmentation_of_pointcloud.cpp.
| double cluster_tolerance = 0.020 | 
[meters]
Definition at line 92 of file segmentation_of_pointcloud.cpp.
| double color_radius = 0.050 | 
Definition at line 96 of file segmentation_of_pointcloud.cpp.
| double epsilon_angle = 0.010 | 
[percentage]
Definition at line 80 of file segmentation_of_pointcloud.cpp.
| bool find_box_model = true | 
Definition at line 109 of file segmentation_of_pointcloud.cpp.
| double fixture_cluster_tolerance = 0.025 | 
[meters]
Definition at line 93 of file segmentation_of_pointcloud.cpp.
| int fixture_min_pts_per_cluster = 150 | 
[points]
Definition at line 100 of file segmentation_of_pointcloud.cpp.
| double handle_clustering_tolerance = 0.050 | 
[points]
Definition at line 89 of file segmentation_of_pointcloud.cpp.
| double height_of_ceiling = 0.050 | 
[percentage]
Definition at line 76 of file segmentation_of_pointcloud.cpp.
| double height_of_floor = 0.025 | 
Definition at line 75 of file segmentation_of_pointcloud.cpp.
| double height_of_walls = 0.750 | 
[percentage]
Definition at line 77 of file segmentation_of_pointcloud.cpp.
| double init_radius = 0.035 | 
Definition at line 95 of file segmentation_of_pointcloud.cpp.
| int maximum_plane_iterations = 1000 | 
[points]
Definition at line 83 of file segmentation_of_pointcloud.cpp.
| int min_pts_per_cluster = 150 | 
Definition at line 99 of file segmentation_of_pointcloud.cpp.
| int minimum_plane_inliers = 1000 | 
[meters]
Definition at line 82 of file segmentation_of_pointcloud.cpp.
| int minimum_size_of_handle_cluster = 25 | 
[meters]
Definition at line 88 of file segmentation_of_pointcloud.cpp.
| int minimum_size_of_plane_cluster = 100 | 
[iterations]
Definition at line 86 of file segmentation_of_pointcloud.cpp.
| double plane_inliers_clustering_tolerance = 0.100 | 
[points]
Definition at line 87 of file segmentation_of_pointcloud.cpp.
| double plane_threshold = 0.100 | 
[radians]
Definition at line 81 of file segmentation_of_pointcloud.cpp.
Definition at line 110 of file segmentation_of_pointcloud.cpp.
| int size_of_points = 1 | 
Definition at line 106 of file segmentation_of_pointcloud.cpp.
| int std_limit = 2 | 
Definition at line 98 of file segmentation_of_pointcloud.cpp.
[points]
Definition at line 103 of file segmentation_of_pointcloud.cpp.
Definition at line 105 of file segmentation_of_pointcloud.cpp.