sac_segmentation.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2012, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: sac_segmentation.h 6155 2012-07-04 23:10:00Z aichim $
00037  *
00038  */
00039 
00040 #ifndef PCL_SEGMENTATION_SAC_SEGMENTATION_H_
00041 #define PCL_SEGMENTATION_SAC_SEGMENTATION_H_
00042 
00043 #include <pcl/pcl_base.h>
00044 #include <pcl/PointIndices.h>
00045 #include <pcl/ModelCoefficients.h>
00046 
00047 // Sample Consensus methods
00048 #include <pcl/sample_consensus/method_types.h>
00049 #include <pcl/sample_consensus/sac.h>
00050 // Sample Consensus models
00051 #include <pcl/sample_consensus/model_types.h>
00052 #include <pcl/sample_consensus/sac_model.h>
00053 
00054 #include <pcl/search/search.h>
00055 
00056 namespace pcl
00057 {
00064   template <typename PointT>
00065   class SACSegmentation : public PCLBase<PointT>
00066   {
00067     using PCLBase<PointT>::initCompute;
00068     using PCLBase<PointT>::deinitCompute;
00069 
00070      public:
00071       using PCLBase<PointT>::input_;
00072       using PCLBase<PointT>::indices_;
00073 
00074       typedef pcl::PointCloud<PointT> PointCloud;
00075       typedef typename PointCloud::Ptr PointCloudPtr;
00076       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00077       typedef typename pcl::search::Search<PointT>::Ptr SearchPtr;
00078 
00079       typedef typename SampleConsensus<PointT>::Ptr SampleConsensusPtr;
00080       typedef typename SampleConsensusModel<PointT>::Ptr SampleConsensusModelPtr;
00081 
00083       SACSegmentation () :  model_ (), sac_ (), model_type_ (-1), method_type_ (0), 
00084                             threshold_ (0), optimize_coefficients_ (true), 
00085                             radius_min_ (-std::numeric_limits<double>::max()), radius_max_ (std::numeric_limits<double>::max()), samples_radius_ (0.0), eps_angle_ (0.0),
00086                             axis_ (Eigen::Vector3f::Zero ()), max_iterations_ (50), probability_ (0.99)
00087       {
00088         //srand ((unsigned)time (0)); // set a random seed
00089       }
00090 
00092       virtual ~SACSegmentation () { /*srv_.reset ();*/ };
00093 
00097       inline void 
00098       setModelType (int model) { model_type_ = model; }
00099 
00101       inline int 
00102       getModelType () const { return (model_type_); }
00103 
00105       inline SampleConsensusPtr 
00106       getMethod () const { return (sac_); }
00107 
00109       inline SampleConsensusModelPtr 
00110       getModel () const { return (model_); }
00111 
00115       inline void 
00116       setMethodType (int method) { method_type_ = method; }
00117 
00119       inline int 
00120       getMethodType () const { return (method_type_); }
00121 
00125       inline void 
00126       setDistanceThreshold (double threshold) { threshold_ = threshold; }
00127 
00129       inline double 
00130       getDistanceThreshold () const { return (threshold_); }
00131 
00135       inline void 
00136       setMaxIterations (int max_iterations) { max_iterations_ = max_iterations; }
00137 
00139       inline int 
00140       getMaxIterations () const { return (max_iterations_); }
00141 
00145       inline void 
00146       setProbability (double probability) { probability_ = probability; }
00147 
00149       inline double 
00150       getProbability () const { return (probability_); }
00151 
00155       inline void 
00156       setOptimizeCoefficients (bool optimize) { optimize_coefficients_ = optimize; }
00157 
00159       inline bool 
00160       getOptimizeCoefficients () const { return (optimize_coefficients_); }
00161 
00167       inline void
00168       setRadiusLimits (const double &min_radius, const double &max_radius)
00169       {
00170         radius_min_ = min_radius;
00171         radius_max_ = max_radius;
00172       }
00173 
00178       inline void
00179       getRadiusLimits (double &min_radius, double &max_radius)
00180       {
00181         min_radius = radius_min_;
00182         max_radius = radius_max_;
00183       }
00184 
00188       inline void
00189       setSamplesMaxDist (const double &radius, SearchPtr search)
00190       {
00191         samples_radius_ = radius;
00192         samples_radius_search_ = search;
00193       }
00194 
00199       inline void
00200       getSamplesMaxDist (double &radius)
00201       {
00202         radius = samples_radius_;
00203       }
00204 
00208       inline void 
00209       setAxis (const Eigen::Vector3f &ax) { axis_ = ax; }
00210 
00212       inline Eigen::Vector3f 
00213       getAxis () const { return (axis_); }
00214 
00218       inline void 
00219       setEpsAngle (double ea) { eps_angle_ = ea; }
00220 
00222       inline double 
00223       getEpsAngle () const { return (eps_angle_); }
00224 
00229       virtual void 
00230       segment (PointIndices &inliers, ModelCoefficients &model_coefficients);
00231 
00232     protected:
00236       virtual bool 
00237       initSACModel (const int model_type);
00238 
00242       virtual void 
00243       initSAC (const int method_type);
00244 
00246       SampleConsensusModelPtr model_;
00247 
00249       SampleConsensusPtr sac_;
00250 
00252       int model_type_;
00253 
00255       int method_type_;
00256 
00258       double threshold_;
00259 
00261       bool optimize_coefficients_;
00262 
00264       double radius_min_, radius_max_;
00265 
00267       double samples_radius_;
00268 
00270       SearchPtr samples_radius_search_;
00271 
00273       double eps_angle_;
00274 
00276       Eigen::Vector3f axis_;
00277 
00279       int max_iterations_;
00280 
00282       double probability_;
00283 
00285       virtual std::string 
00286       getClassName () const { return ("SACSegmentation"); }
00287   };
00288 
00293   template <typename PointT, typename PointNT>
00294   class SACSegmentationFromNormals: public SACSegmentation<PointT>
00295   {
00296     using SACSegmentation<PointT>::model_;
00297     using SACSegmentation<PointT>::model_type_;
00298     using SACSegmentation<PointT>::radius_min_;
00299     using SACSegmentation<PointT>::radius_max_;
00300     using SACSegmentation<PointT>::eps_angle_;
00301     using SACSegmentation<PointT>::axis_;
00302 
00303     public:
00304       using PCLBase<PointT>::input_;
00305       using PCLBase<PointT>::indices_;
00306 
00307       typedef typename SACSegmentation<PointT>::PointCloud PointCloud;
00308       typedef typename PointCloud::Ptr PointCloudPtr;
00309       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00310 
00311       typedef typename pcl::PointCloud<PointNT> PointCloudN;
00312       typedef typename PointCloudN::Ptr PointCloudNPtr;
00313       typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;
00314 
00315       typedef typename SampleConsensus<PointT>::Ptr SampleConsensusPtr;
00316       typedef typename SampleConsensusModel<PointT>::Ptr SampleConsensusModelPtr;
00317       typedef typename SampleConsensusModelFromNormals<PointT, PointNT>::Ptr SampleConsensusModelFromNormalsPtr;
00318 
00320       SACSegmentationFromNormals () : 
00321         normals_ (), 
00322         distance_weight_ (0.1), 
00323         distance_from_origin_ (0), 
00324         min_angle_ (), 
00325         max_angle_ ()
00326       {};
00327 
00332       inline void 
00333       setInputNormals (const PointCloudNConstPtr &normals) { normals_ = normals; }
00334 
00336       inline PointCloudNConstPtr 
00337       getInputNormals () const { return (normals_); }
00338 
00343       inline void 
00344       setNormalDistanceWeight (double distance_weight) { distance_weight_ = distance_weight; }
00345 
00348       inline double 
00349       getNormalDistanceWeight () const { return (distance_weight_); }
00350 
00354       inline void
00355       setMinMaxOpeningAngle (const double &min_angle, const double &max_angle)
00356       {
00357         min_angle_ = min_angle;
00358         max_angle_ = max_angle;
00359       }
00360  
00362       inline void
00363       getMinMaxOpeningAngle (double &min_angle, double &max_angle)
00364       {
00365         min_angle = min_angle_;
00366         max_angle = max_angle_;
00367       }
00368 
00372       inline void
00373       setDistanceFromOrigin (const double d) { distance_from_origin_ = d; }
00374 
00376       inline double
00377       getDistanceFromOrigin () const { return (distance_from_origin_); }
00378 
00379     protected:
00381       PointCloudNConstPtr normals_;
00382 
00386       double distance_weight_;
00387 
00389       double distance_from_origin_;
00390 
00392       double min_angle_;
00393       double max_angle_;
00394 
00398       virtual bool 
00399       initSACModel (const int model_type);
00400 
00402       virtual std::string 
00403       getClassName () const { return ("SACSegmentationFromNormals"); }
00404   };
00405 }
00406 
00407 #endif  //#ifndef PCL_SEGMENTATION_SAC_SEGMENTATION_H_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:17:50