ransac.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 RANSAC_H_
00057 #define RANSAC_H_
00058 
00059 #include <visualization_msgs/MarkerArray.h>
00060 
00061 #include <pcl/sample_consensus/ransac.h>
00062 #include <pcl/sample_consensus/sac_model_plane.h>
00063 #include <pcl/sample_consensus/sac_model_cylinder.h>
00064 #include <pcl/sample_consensus/sac_model_sphere.h>
00065 #include <pcl/filters/extract_indices.h>
00066 
00067 #include "../general_segmentation.h"
00068 
00069 namespace Segmentation
00070 {
00071 
00075   template <typename Point, typename PointLabel>
00076   class Segmentation_RANSAC : public GeneralSegmentation<Point, PointLabel>
00077   {
00078 
00079     struct SHAPE_S {
00080       Eigen::VectorXf coeff_;
00081       std::vector<int> inliers_;
00082       enum {PLANE=1, CYLINDER=2, SPHERE=3} type_;
00083     };
00084 
00085     boost::shared_ptr<const pcl::PointCloud<Point> > input_;
00086     std::vector<SHAPE_S> shapes_;
00087 
00088     bool planes_, cylinders_, spheres_;
00089 
00090   public:
00092     Segmentation_RANSAC() : planes_(true), cylinders_(true), spheres_(true)
00093     {}
00094 
00096     virtual ~Segmentation_RANSAC() {
00097     }
00098 
00100     virtual void setInputCloud (const boost::shared_ptr<const pcl::PointCloud<Point> > &cloud)
00101     {
00102       input_ = cloud;
00103      /* pcl::PointCloud<Point> *pc = new pcl::PointCloud<Point>;
00104       pc->header = cloud->header;
00105       pc->width  = cloud->width /2;
00106       pc->height = cloud->height/2;
00107       pc->resize(pc->width*pc->height);
00108 
00109       for(size_t x=0; x<pc->width; x++) {
00110         for(size_t y=0; y<pc->height; y++) {
00111           (*pc)(x,y) = (*cloud)(2*x,2*y);
00112           (*pc)(x,y).x = ((*cloud)(2*x,2*y).x+(*cloud)(2*x+1,2*y).x+(*cloud)(2*x,2*y+1).x+(*cloud)(2*x+1,2*y+1).x)/4;
00113           (*pc)(x,y).y = ((*cloud)(2*x,2*y).y+(*cloud)(2*x+1,2*y).y+(*cloud)(2*x,2*y+1).y+(*cloud)(2*x+1,2*y+1).y)/4;
00114           (*pc)(x,y).z = ((*cloud)(2*x,2*y).z+(*cloud)(2*x+1,2*y).z+(*cloud)(2*x,2*y+1).z+(*cloud)(2*x+1,2*y+1).z)/4;
00115         }
00116       }
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, 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);
00128 
00129     void enablePlanes(const bool b) {planes_=b;}
00130     void enableSpheres(const bool b) {spheres_=b;}
00131     void enableCylinders(const bool b) {cylinders_=b;}
00132 
00134     virtual boost::shared_ptr<const pcl::PointCloud<PointLabel> > getReconstructedOutputCloud();
00135 
00137     virtual boost::shared_ptr<const pcl::PointCloud<PointLabel> > getOutputCloud () {return getReconstructedOutputCloud();}
00138 
00140     virtual operator cob_3d_mapping_msgs::ShapeArray() const {return cob_3d_mapping_msgs::ShapeArray();}
00141   };
00142 
00143 #include "impl/ransac.hpp"
00144 
00145 }
00146 
00147 
00148 
00149 #endif /* RANSAC_H_ */


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