Go to the documentation of this file.00001 #ifndef _SURFACE_PERCEPTION_SEGMENTATION_H_
00002 #define _SURFACE_PERCEPTION_SEGMENTATION_H_
00003
00004 #include <vector>
00005
00006 #include "pcl/PointIndices.h"
00007 #include "pcl/point_cloud.h"
00008 #include "pcl/point_types.h"
00009
00010 #include "surface_perception/surface.h"
00011 #include "surface_perception/surface_objects.h"
00012
00013 namespace surface_perception {
00042 class Segmentation {
00043 public:
00045 Segmentation();
00046
00050 void set_input_cloud(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud);
00051
00053 void set_indices(pcl::PointIndicesPtr indices);
00054
00059 void set_horizontal_tolerance_degrees(double degrees);
00060
00070 void set_margin_above_surface(double margin);
00071
00080 void set_cluster_distance(double cluster_distance);
00081
00090 void set_min_cluster_size(int min_cluster_size);
00091
00101 void set_max_cluster_size(int max_cluster_size);
00102
00111 void set_min_surface_size(int min_surface_size);
00112
00124 void set_min_surface_exploration_iteration(
00125 int min_surface_exploration_iteration);
00126
00137 void set_max_point_distance(double max_point_distance);
00138
00148 bool Segment(std::vector<SurfaceObjects>* surfaces) const;
00149
00150 private:
00151 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_;
00152 pcl::PointIndicesPtr indices_;
00153
00154 double horizontal_tolerance_degrees_;
00155 double margin_above_surface_;
00156 double cluster_distance_;
00157 double max_point_distance_;
00158 int min_cluster_size_;
00159 int max_cluster_size_;
00160 int min_surface_size_;
00161 int min_surface_exploration_iteration_;
00162 };
00163
00180 bool FindSurfaces(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
00181 pcl::PointIndicesPtr indices, double max_point_distance,
00182 double horizontal_tolerance_degrees, int min_surface_size,
00183 int min_surface_exploration_iteration,
00184 std::vector<Surface>* surfaces);
00185
00205 bool GetSceneAboveSurface(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
00206 pcl::PointIndicesPtr indices,
00207 const pcl::ModelCoefficients& coefficients,
00208 double margin_above_surface, float height_limit,
00209 pcl::PointIndices::Ptr above_surface_indices);
00210
00230 bool FindObjectsOnSurfaces(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
00231 pcl::PointIndicesPtr indices,
00232 const std::vector<Surface>& surface_vec,
00233 double margin_above_surface, double cluster_distance,
00234 int min_cluster_size, int max_cluster_size,
00235 std::vector<SurfaceObjects>* surfaces_objects_vec);
00236 }
00237
00238 #endif // _SURFACE_PERCEPTION_SEGMENTATION_H_