Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 
00039 
00040 
00041 
00042 
00043 
00044 
00045 
00046 
00047 
00048 
00049 
00050 
00051 
00052 
00053 
00054 
00055 #ifndef MULTIPLANE_H_
00056 #define MULTIPLANE_H_
00057 
00058 #include <visualization_msgs/MarkerArray.h>
00059 
00060 #include <pcl/search/organized.h>
00061 #include <pcl/features/integral_image_normal.h>
00062 #include <pcl/segmentation/organized_multi_plane_segmentation.h>
00063 #include <pcl/segmentation/edge_aware_plane_comparator.h>
00064 #include <pcl/filters/extract_indices.h>
00065 
00066 #include "../general_segmentation.h"
00067 
00068 namespace Segmentation
00069 {
00070 
00074   template <typename Point, typename PointTypeNormal, typename PointLabel>
00075   class Segmentation_MultiPlane : public GeneralSegmentation<Point, PointLabel>
00076   {
00077     std::vector<typename pcl::PlanarRegion<Point>, Eigen::aligned_allocator<typename pcl::PlanarRegion<Point> > > regions;
00078     std::vector<pcl::ModelCoefficients> coef;
00079     std::vector<pcl::PointIndices> inlier_indices;
00080     std::vector<pcl::PointIndices> label_indices;
00081     std::vector<pcl::PointIndices> boundary_indices;
00082     pcl::PointCloud<pcl::Label>::Ptr l;
00083 
00084     boost::shared_ptr<const pcl::PointCloud<Point> > input_;
00085 
00086   public:
00088     Segmentation_MultiPlane()
00089     {}
00090 
00092     virtual ~Segmentation_MultiPlane() {
00093     }
00094 
00096     virtual void setInputCloud (const boost::shared_ptr<const pcl::PointCloud<Point> > &cloud)
00097     {
00098       input_ = cloud;
00099     }
00100 
00101     virtual bool compute();
00102 
00104     operator visualization_msgs::Marker() const;
00105 
00106     
00107     void compute_accuracy(float &mean, float &var, float &mean_weighted, float &var_weighted, size_t &used, size_t &mem, size_t &points, float &avg_dist, const boost::shared_ptr<const pcl::PointCloud<PointLabel> > &labeled_pc, double &true_positive, double &false_positive);
00108 
00110     virtual boost::shared_ptr<const pcl::PointCloud<PointLabel> > getReconstructedOutputCloud();
00111 
00113     virtual boost::shared_ptr<const pcl::PointCloud<PointLabel> > getOutputCloud () {return getReconstructedOutputCloud();}
00114 
00116     virtual operator cob_3d_mapping_msgs::ShapeArray() const {return cob_3d_mapping_msgs::ShapeArray();}
00117   };
00118 
00119 #include "impl/multi_plane.hpp"
00120 
00121 }
00122 
00123 
00124 
00125 #endif