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
00056 #ifndef MARCHING_CUBES_H_
00057 #define MARCHING_CUBES_H_
00058
00059 #include <visualization_msgs/MarkerArray.h>
00060
00061 #if !defined(PCL_VERSION_COMPARE) || PCL_MINOR_VERSION < 6
00062
00063 #define USE_GREEDY
00064 #endif
00065
00066 #include <pcl/surface/marching_cubes.h>
00067 #ifdef USE_GREEDY
00068 #include <pcl/surface/marching_cubes_greedy.h>
00069 #define MARCHING_CUBES_INST MarchingCubesGreedy
00070 #else
00071 #include <pcl/surface/marching_cubes_rbf.h>
00072 #define MARCHING_CUBES_INST MarchingCubesRBF
00073 #endif
00074 #include <pcl/features/normal_3d.h>
00075 #include <pcl/kdtree/kdtree_flann.h>
00076
00077 #include "../general_segmentation.h"
00078
00079 namespace Segmentation
00080 {
00081
00085 template <typename Point, typename PointTypeNormal, typename PointLabel>
00086 class Segmentation_MarchingCubes : public GeneralSegmentation<Point, PointLabel>
00087 {
00088
00089 boost::shared_ptr<const pcl::PointCloud<Point> > input_;
00090 pcl::PolygonMesh mesh_;
00091
00092 float leafSize_;
00093 float isoLevel_;
00094
00095 public:
00097 Segmentation_MarchingCubes() : leafSize_(0.025), isoLevel_(0.02f)
00098 {}
00099
00101 virtual ~Segmentation_MarchingCubes() {
00102 }
00103
00105 virtual void setInputCloud (const boost::shared_ptr<const pcl::PointCloud<Point> > &cloud)
00106 {
00107 pcl::PointCloud<Point> *pc = new pcl::PointCloud<Point>;
00108 pc->header = cloud->header;
00109 pc->height = 1;
00110
00111 for(size_t x=0; x<cloud->size(); x++) {
00112 if(pcl_isfinite((*cloud)[x].x))
00113 pc->push_back((*cloud)[x]);
00114 }
00115
00116 pc->width = pc->size();
00117
00118 input_.reset(pc);
00119 }
00120
00121 virtual bool compute();
00122
00124 operator visualization_msgs::Marker() const;
00125
00126
00127 void compute_accuracy(float &mean, float &var, size_t &used, size_t &mem, size_t &points, float &avg_dist);
00128
00130 virtual boost::shared_ptr<const pcl::PointCloud<PointLabel> > getReconstructedOutputCloud();
00131
00133 virtual boost::shared_ptr<const pcl::PointCloud<PointLabel> > getOutputCloud () {return getReconstructedOutputCloud();}
00134
00136 virtual operator cob_3d_mapping_msgs::ShapeArray() const {return cob_3d_mapping_msgs::ShapeArray();}
00137 };
00138
00139 #include "impl/marching_cubes.hpp"
00140
00141 }
00142
00143
00144
00145 #endif