marching_cubes.h
Go to the documentation of this file.
00001 
00002 /****************************************************************
00003  *
00004  * Copyright (c) 2011
00005  *
00006  * Fraunhofer Institute for Manufacturing Engineering
00007  * and Automation (IPA)
00008  *
00009  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00010  *
00011  * Project name: care-o-bot
00012  * ROS stack name: cob_vision
00013  * ROS package name: dynamic_tutorials
00014  * Description:
00015  *
00016  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00017  *
00018  * Author: josh
00019  *
00020  * Date of creation: Oct 26, 2011
00021  * ToDo:
00022  *
00023  *
00024  *
00025  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00026  *
00027  * Redistribution and use in source and binary forms, with or without
00028  * modification, are permitted provided that the following conditions are met:
00029  *
00030  *     * Redistributions of source code must retain the above copyright
00031  *       notice, this list of conditions and the following disclaimer.
00032  *     * Redistributions in binary form must reproduce the above copyright
00033  *       notice, this list of conditions and the following disclaimer in the
00034  *       documentation and/or other materials provided with the distribution.
00035  *     * Neither the name of the Fraunhofer Institute for Manufacturing
00036  *       Engineering and Automation (IPA) nor the names of its
00037  *       contributors may be used to endorse or promote products derived from
00038  *       this software without specific prior written permission.
00039  *
00040  * This program is free software: you can redistribute it and/or modify
00041  * it under the terms of the GNU Lesser General Public License LGPL as
00042  * published by the Free Software Foundation, either version 3 of the
00043  * License, or (at your option) any later version.
00044  *
00045  * This program is distributed in the hope that it will be useful,
00046  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00047  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00048  * GNU Lesser General Public License LGPL for more details.
00049  *
00050  * You should have received a copy of the GNU Lesser General Public
00051  * License LGPL along with this program.
00052  * If not, see <http://www.gnu.org/licenses/>.
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 //#ifndef PCL_VERSION_COMPARE
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     /*** evaluation purposes ***/
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 /* MARCHING_CUBES_H_ */


cob_3d_segmentation
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:03:03