project_inliers.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder(s) nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id$
00035  *
00036  */
00037 
00038 #ifndef PCL_FILTERS_PROJECT_INLIERS_H_
00039 #define PCL_FILTERS_PROJECT_INLIERS_H_
00040 
00041 #include <pcl/point_types.h>
00042 #include <pcl/filters/filter.h>
00043 #include <pcl/ModelCoefficients.h>
00044 // Sample Consensus models
00045 #include <pcl/sample_consensus/model_types.h>
00046 #include <pcl/sample_consensus/sac_model.h>
00047 #include <pcl/sample_consensus/sac_model_circle.h>
00048 #include <pcl/sample_consensus/sac_model_cylinder.h>
00049 #include <pcl/sample_consensus/sac_model_cone.h>
00050 #include <pcl/sample_consensus/sac_model_line.h>
00051 #include <pcl/sample_consensus/sac_model_normal_plane.h>
00052 #include <pcl/sample_consensus/sac_model_normal_sphere.h>
00053 #include <pcl/sample_consensus/sac_model_parallel_plane.h>
00054 #include <pcl/sample_consensus/sac_model_normal_parallel_plane.h>
00055 #include <pcl/sample_consensus/sac_model_parallel_line.h>
00056 #include <pcl/sample_consensus/sac_model_perpendicular_plane.h>
00057 #include <pcl/sample_consensus/sac_model_plane.h>
00058 #include <pcl/sample_consensus/sac_model_sphere.h>
00059 
00060 namespace pcl
00061 {
00063 
00068   template<typename PointT>
00069   class ProjectInliers : public Filter<PointT>
00070   {
00071     using Filter<PointT>::input_;
00072     using Filter<PointT>::indices_;
00073     using Filter<PointT>::filter_name_;
00074     using Filter<PointT>::getClassName;
00075 
00076     typedef typename Filter<PointT>::PointCloud PointCloud;
00077     typedef typename PointCloud::Ptr PointCloudPtr;
00078     typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00079 
00080     typedef typename SampleConsensusModel<PointT>::Ptr SampleConsensusModelPtr;
00081     public:
00082 
00083       typedef boost::shared_ptr< ProjectInliers<PointT> > Ptr;
00084       typedef boost::shared_ptr< const ProjectInliers<PointT> > ConstPtr;
00085 
00086 
00088       ProjectInliers () : model_ (), sacmodel_ (), model_type_ (), copy_all_data_ (false)
00089       {
00090         filter_name_ = "ProjectInliers";
00091       }
00092       
00094       virtual ~ProjectInliers () {}
00095 
00099       inline void
00100       setModelType (int model)
00101       {
00102         model_type_ = model;
00103       }
00104 
00106       inline int
00107       getModelType ()
00108       {
00109         return (model_type_);
00110       }
00111 
00115       inline void
00116       setModelCoefficients (const ModelCoefficientsConstPtr &model)
00117       {
00118         model_ = model;
00119       }
00120 
00122       inline ModelCoefficientsConstPtr
00123       getModelCoefficients ()
00124       {
00125         return (model_);
00126       }
00127 
00131       inline void
00132       setCopyAllData (bool val)
00133       {
00134         copy_all_data_ = val;
00135       }
00136 
00138       inline bool
00139       getCopyAllData ()
00140       {
00141         return (copy_all_data_);
00142       }
00143     protected:
00145 
00148       void
00149       applyFilter (PointCloud &output);
00150 
00151     private:
00153       ModelCoefficientsConstPtr model_;
00154 
00156       SampleConsensusModelPtr sacmodel_;
00157 
00159       int model_type_;
00160 
00162       bool copy_all_data_;
00163 
00167       virtual bool
00168       initSACModel (int model_type);
00169   };
00170 
00172 
00178   template<>
00179   class PCL_EXPORTS ProjectInliers<pcl::PCLPointCloud2> : public Filter<pcl::PCLPointCloud2>
00180   {
00181     using Filter<pcl::PCLPointCloud2>::filter_name_;
00182     using Filter<pcl::PCLPointCloud2>::getClassName;
00183 
00184     typedef pcl::PCLPointCloud2 PCLPointCloud2;
00185     typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr;
00186     typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr;
00187 
00188     typedef SampleConsensusModel<PointXYZ>::Ptr SampleConsensusModelPtr;
00189 
00190     public:
00192       ProjectInliers () : model_type_ (), copy_all_data_ (false), copy_all_fields_ (true), model_ (), sacmodel_ ()
00193       {
00194         filter_name_ = "ProjectInliers";
00195       }
00196       
00198       virtual ~ProjectInliers () {}
00199 
00203       inline void
00204       setModelType (int model)
00205       {
00206         model_type_ = model;
00207       }
00208 
00210       inline int
00211       getModelType () const
00212       {
00213         return (model_type_);
00214       }
00215 
00219       inline void
00220       setModelCoefficients (const ModelCoefficientsConstPtr &model)
00221       {
00222         model_ = model;
00223       }
00224 
00226       inline ModelCoefficientsConstPtr
00227       getModelCoefficients () const
00228       {
00229         return (model_);
00230       }
00231 
00235       inline void
00236       setCopyAllFields (bool val)
00237       {
00238         copy_all_fields_ = val;
00239       }
00240 
00242       inline bool
00243       getCopyAllFields () const
00244       {
00245         return (copy_all_fields_);
00246       }
00247 
00251       inline void
00252       setCopyAllData (bool val)
00253       {
00254         copy_all_data_ = val;
00255       }
00256 
00258       inline bool
00259       getCopyAllData () const
00260       {
00261         return (copy_all_data_);
00262       }
00263     protected:
00265       int model_type_;
00266 
00268       bool copy_all_data_;
00269 
00271       bool copy_all_fields_;
00272 
00274       ModelCoefficientsConstPtr model_;
00275 
00276       void
00277       applyFilter (PCLPointCloud2 &output);
00278 
00279     private:
00281       SampleConsensusModelPtr sacmodel_;
00282 
00283       virtual bool
00284       initSACModel (int model_type);
00285   };
00286 }
00287 
00288 #ifdef PCL_NO_PRECOMPILE
00289 #include <pcl/filters/impl/project_inliers.hpp>
00290 #endif
00291 
00292 #endif  //#ifndef PCL_FILTERS_PROJECT_INLIERS_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:31:29