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 the copyright holder(s) 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$
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 
00085       SACSegmentation (bool random = false) 
00086         : model_ ()
00087         , sac_ ()
00088         , model_type_ (-1)
00089         , method_type_ (0)
00090         , threshold_ (0)
00091         , optimize_coefficients_ (true)
00092         , radius_min_ (-std::numeric_limits<double>::max ())
00093         , radius_max_ (std::numeric_limits<double>::max ())
00094         , samples_radius_ (0.0)
00095         , samples_radius_search_ ()
00096         , eps_angle_ (0.0)
00097         , axis_ (Eigen::Vector3f::Zero ())
00098         , max_iterations_ (50)
00099         , probability_ (0.99)
00100         , random_ (random)
00101       {
00102       }
00103 
00105       virtual ~SACSegmentation () { /*srv_.reset ();*/ };
00106 
00110       inline void 
00111       setModelType (int model) { model_type_ = model; }
00112 
00114       inline int 
00115       getModelType () const { return (model_type_); }
00116 
00118       inline SampleConsensusPtr 
00119       getMethod () const { return (sac_); }
00120 
00122       inline SampleConsensusModelPtr 
00123       getModel () const { return (model_); }
00124 
00128       inline void 
00129       setMethodType (int method) { method_type_ = method; }
00130 
00132       inline int 
00133       getMethodType () const { return (method_type_); }
00134 
00138       inline void 
00139       setDistanceThreshold (double threshold) { threshold_ = threshold; }
00140 
00142       inline double 
00143       getDistanceThreshold () const { return (threshold_); }
00144 
00148       inline void 
00149       setMaxIterations (int max_iterations) { max_iterations_ = max_iterations; }
00150 
00152       inline int 
00153       getMaxIterations () const { return (max_iterations_); }
00154 
00158       inline void 
00159       setProbability (double probability) { probability_ = probability; }
00160 
00162       inline double 
00163       getProbability () const { return (probability_); }
00164 
00168       inline void 
00169       setOptimizeCoefficients (bool optimize) { optimize_coefficients_ = optimize; }
00170 
00172       inline bool 
00173       getOptimizeCoefficients () const { return (optimize_coefficients_); }
00174 
00180       inline void
00181       setRadiusLimits (const double &min_radius, const double &max_radius)
00182       {
00183         radius_min_ = min_radius;
00184         radius_max_ = max_radius;
00185       }
00186 
00191       inline void
00192       getRadiusLimits (double &min_radius, double &max_radius)
00193       {
00194         min_radius = radius_min_;
00195         max_radius = radius_max_;
00196       }
00197 
00201       inline void
00202       setSamplesMaxDist (const double &radius, SearchPtr search)
00203       {
00204         samples_radius_ = radius;
00205         samples_radius_search_ = search;
00206       }
00207 
00212       inline void
00213       getSamplesMaxDist (double &radius)
00214       {
00215         radius = samples_radius_;
00216       }
00217 
00221       inline void 
00222       setAxis (const Eigen::Vector3f &ax) { axis_ = ax; }
00223 
00225       inline Eigen::Vector3f 
00226       getAxis () const { return (axis_); }
00227 
00231       inline void 
00232       setEpsAngle (double ea) { eps_angle_ = ea; }
00233 
00235       inline double 
00236       getEpsAngle () const { return (eps_angle_); }
00237 
00242       virtual void 
00243       segment (PointIndices &inliers, ModelCoefficients &model_coefficients);
00244 
00245     protected:
00249       virtual bool 
00250       initSACModel (const int model_type);
00251 
00255       virtual void 
00256       initSAC (const int method_type);
00257 
00259       SampleConsensusModelPtr model_;
00260 
00262       SampleConsensusPtr sac_;
00263 
00265       int model_type_;
00266 
00268       int method_type_;
00269 
00271       double threshold_;
00272 
00274       bool optimize_coefficients_;
00275 
00277       double radius_min_, radius_max_;
00278 
00280       double samples_radius_;
00281 
00283       SearchPtr samples_radius_search_;
00284 
00286       double eps_angle_;
00287 
00289       Eigen::Vector3f axis_;
00290 
00292       int max_iterations_;
00293 
00295       double probability_;
00296 
00298       bool random_;
00299 
00301       virtual std::string 
00302       getClassName () const { return ("SACSegmentation"); }
00303   };
00304 
00309   template <typename PointT, typename PointNT>
00310   class SACSegmentationFromNormals: public SACSegmentation<PointT>
00311   {
00312     using SACSegmentation<PointT>::model_;
00313     using SACSegmentation<PointT>::model_type_;
00314     using SACSegmentation<PointT>::radius_min_;
00315     using SACSegmentation<PointT>::radius_max_;
00316     using SACSegmentation<PointT>::eps_angle_;
00317     using SACSegmentation<PointT>::axis_;
00318     using SACSegmentation<PointT>::random_;
00319 
00320     public:
00321       using PCLBase<PointT>::input_;
00322       using PCLBase<PointT>::indices_;
00323 
00324       typedef typename SACSegmentation<PointT>::PointCloud PointCloud;
00325       typedef typename PointCloud::Ptr PointCloudPtr;
00326       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00327 
00328       typedef typename pcl::PointCloud<PointNT> PointCloudN;
00329       typedef typename PointCloudN::Ptr PointCloudNPtr;
00330       typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;
00331 
00332       typedef typename SampleConsensus<PointT>::Ptr SampleConsensusPtr;
00333       typedef typename SampleConsensusModel<PointT>::Ptr SampleConsensusModelPtr;
00334       typedef typename SampleConsensusModelFromNormals<PointT, PointNT>::Ptr SampleConsensusModelFromNormalsPtr;
00335 
00339       SACSegmentationFromNormals (bool random = false) 
00340         : SACSegmentation<PointT> (random)
00341         , normals_ ()
00342         , distance_weight_ (0.1)
00343         , distance_from_origin_ (0)
00344         , min_angle_ ()
00345         , max_angle_ ()
00346       {};
00347 
00352       inline void 
00353       setInputNormals (const PointCloudNConstPtr &normals) { normals_ = normals; }
00354 
00356       inline PointCloudNConstPtr 
00357       getInputNormals () const { return (normals_); }
00358 
00363       inline void 
00364       setNormalDistanceWeight (double distance_weight) { distance_weight_ = distance_weight; }
00365 
00368       inline double 
00369       getNormalDistanceWeight () const { return (distance_weight_); }
00370 
00374       inline void
00375       setMinMaxOpeningAngle (const double &min_angle, const double &max_angle)
00376       {
00377         min_angle_ = min_angle;
00378         max_angle_ = max_angle;
00379       }
00380  
00382       inline void
00383       getMinMaxOpeningAngle (double &min_angle, double &max_angle)
00384       {
00385         min_angle = min_angle_;
00386         max_angle = max_angle_;
00387       }
00388 
00392       inline void
00393       setDistanceFromOrigin (const double d) { distance_from_origin_ = d; }
00394 
00396       inline double
00397       getDistanceFromOrigin () const { return (distance_from_origin_); }
00398 
00399     protected:
00401       PointCloudNConstPtr normals_;
00402 
00406       double distance_weight_;
00407 
00409       double distance_from_origin_;
00410 
00412       double min_angle_;
00413       double max_angle_;
00414 
00418       virtual bool 
00419       initSACModel (const int model_type);
00420 
00422       virtual std::string 
00423       getClassName () const { return ("SACSegmentationFromNormals"); }
00424   };
00425 }
00426 
00427 #ifdef PCL_NO_PRECOMPILE
00428 #include <pcl/segmentation/impl/sac_segmentation.hpp>
00429 #endif
00430 
00431 #endif  //#ifndef PCL_SEGMENTATION_SAC_SEGMENTATION_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:32:36