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


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