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 Willow Garage, Inc. 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: project_inliers.h 6144 2012-07-04 22:06:28Z rusu $
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:
00083       ProjectInliers () : model_ (), sacmodel_ (), model_type_ (), copy_all_data_ (false)
00084       {
00085         filter_name_ = "ProjectInliers";
00086       }
00087 
00091       inline void
00092       setModelType (int model)
00093       {
00094         model_type_ = model;
00095       }
00096 
00098       inline int
00099       getModelType ()
00100       {
00101         return (model_type_);
00102       }
00103 
00107       inline void
00108       setModelCoefficients (const ModelCoefficientsConstPtr &model)
00109       {
00110         model_ = model;
00111       }
00112 
00114       inline ModelCoefficientsConstPtr
00115       getModelCoefficients ()
00116       {
00117         return (model_);
00118       }
00119 
00123       inline void
00124       setCopyAllData (bool val)
00125       {
00126         copy_all_data_ = val;
00127       }
00128 
00130       inline bool
00131       getCopyAllData ()
00132       {
00133         return (copy_all_data_);
00134       }
00135     protected:
00137 
00140       void
00141       applyFilter (PointCloud &output);
00142 
00143     private:
00145       ModelCoefficientsConstPtr model_;
00146 
00148       SampleConsensusModelPtr sacmodel_;
00149 
00151       int model_type_;
00152 
00154       bool copy_all_data_;
00155 
00159       virtual bool
00160       initSACModel (int model_type);
00161   };
00162 
00164 
00170   template<>
00171   class PCL_EXPORTS ProjectInliers<sensor_msgs::PointCloud2> : public Filter<sensor_msgs::PointCloud2>
00172   {
00173     using Filter<sensor_msgs::PointCloud2>::filter_name_;
00174     using Filter<sensor_msgs::PointCloud2>::getClassName;
00175 
00176     typedef sensor_msgs::PointCloud2 PointCloud2;
00177     typedef PointCloud2::Ptr PointCloud2Ptr;
00178     typedef PointCloud2::ConstPtr PointCloud2ConstPtr;
00179 
00180     typedef SampleConsensusModel<PointXYZ>::Ptr SampleConsensusModelPtr;
00181 
00182     public:
00184       ProjectInliers () : model_type_ (), copy_all_data_ (false), copy_all_fields_ (true), model_ (), sacmodel_ ()
00185       {
00186         filter_name_ = "ProjectInliers";
00187       }
00188 
00192       inline void
00193       setModelType (int model)
00194       {
00195         model_type_ = model;
00196       }
00197 
00199       inline int
00200       getModelType () const
00201       {
00202         return (model_type_);
00203       }
00204 
00208       inline void
00209       setModelCoefficients (const ModelCoefficientsConstPtr &model)
00210       {
00211         model_ = model;
00212       }
00213 
00215       inline ModelCoefficientsConstPtr
00216       getModelCoefficients () const
00217       {
00218         return (model_);
00219       }
00220 
00224       inline void
00225       setCopyAllFields (bool val)
00226       {
00227         copy_all_fields_ = val;
00228       }
00229 
00231       inline bool
00232       getCopyAllFields () const
00233       {
00234         return (copy_all_fields_);
00235       }
00236 
00240       inline void
00241       setCopyAllData (bool val)
00242       {
00243         copy_all_data_ = val;
00244       }
00245 
00247       inline bool
00248       getCopyAllData () const
00249       {
00250         return (copy_all_data_);
00251       }
00252     protected:
00254       int model_type_;
00255 
00257       bool copy_all_data_;
00258 
00260       bool copy_all_fields_;
00261 
00263       ModelCoefficientsConstPtr model_;
00264 
00265       void
00266       applyFilter (PointCloud2 &output);
00267 
00268     private:
00270       SampleConsensusModelPtr sacmodel_;
00271 
00272       virtual bool
00273       initSACModel (int model_type);
00274   };
00275 }
00276 
00277 #endif  //#ifndef PCL_FILTERS_PROJECT_INLIERS_H_


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