project_inliers.hpp
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.hpp 5026 2012-03-12 02:51:44Z rusu $
00035  *
00036  */
00037 
00038 #ifndef PCL_FILTERS_IMPL_PROJECT_INLIERS_H_
00039 #define PCL_FILTERS_IMPL_PROJECT_INLIERS_H_
00040 
00041 #include <pcl/filters/project_inliers.h>
00042 
00044 template <typename PointT> void
00045 pcl::ProjectInliers<PointT>::applyFilter (PointCloud &output)
00046 {
00047   if (indices_->empty ())
00048   {
00049     PCL_WARN ("[pcl::%s::applyFilter] No indices given or empty indices!\n", getClassName ().c_str ());
00050     output.width = output.height = 0;
00051     output.points.clear ();
00052     return;
00053   }
00054 
00055   //Eigen::Map<Eigen::VectorXf, Eigen::Aligned> model_coefficients (&model_->values[0], model_->values.size ());
00056   // More expensive than a map but safer (32bit architectures seem to complain)
00057   Eigen::VectorXf model_coefficients (model_->values.size ());
00058   for (size_t i = 0; i < model_->values.size (); ++i)
00059     model_coefficients[i] = model_->values[i];
00060 
00061   // Initialize the Sample Consensus model and set its parameters
00062   if (!initSACModel (model_type_))
00063   {
00064     PCL_ERROR ("[pcl::%s::segment] Error initializing the SAC model!\n", getClassName ().c_str ());
00065     output.width = output.height = 0;
00066     output.points.clear ();
00067     return;
00068   }
00069   if (copy_all_data_)
00070     sacmodel_->projectPoints (*indices_, model_coefficients, output, true);
00071   else
00072     sacmodel_->projectPoints (*indices_, model_coefficients, output, false);
00073 }
00074 
00076 template <typename PointT> bool
00077 pcl::ProjectInliers<PointT>::initSACModel (int model_type)
00078 {
00079   // Build the model
00080   switch (model_type)
00081   {
00082     case SACMODEL_PLANE:
00083     {
00084       //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_PLANE\n", getClassName ().c_str ());
00085       sacmodel_.reset (new SampleConsensusModelPlane<PointT> (input_));
00086       break;
00087     }
00088     case SACMODEL_LINE:
00089     {
00090       //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_LINE\n", getClassName ().c_str ());
00091       sacmodel_.reset (new SampleConsensusModelLine<PointT> (input_));
00092       break;
00093     }
00094     case SACMODEL_CIRCLE2D:
00095     {
00096       //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_CIRCLE2D\n", getClassName ().c_str ());
00097       sacmodel_.reset (new SampleConsensusModelCircle2D<PointT> (input_));
00098       break;
00099     }
00100     case SACMODEL_SPHERE:
00101     {
00102       //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_SPHERE\n", getClassName ().c_str ());
00103       sacmodel_.reset (new SampleConsensusModelSphere<PointT> (input_));
00104       break;
00105     }
00106     case SACMODEL_PARALLEL_LINE:
00107     {
00108       //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_PARALLEL_LINE\n", getClassName ().c_str ());
00109       sacmodel_.reset (new SampleConsensusModelParallelLine<PointT> (input_));
00110       break;
00111     }
00112     case SACMODEL_PERPENDICULAR_PLANE:
00113     {
00114       //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_PERPENDICULAR_PLANE\n", getClassName ().c_str ());
00115       sacmodel_.reset (new SampleConsensusModelPerpendicularPlane<PointT> (input_));
00116       break;
00117     }
00118     case SACMODEL_CYLINDER:
00119     {
00120       //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_CYLINDER\n", getClassName ().c_str ());
00121       sacmodel_.reset (new SampleConsensusModelCylinder<PointT, pcl::Normal> (input_));
00122       break;
00123     }
00124     case SACMODEL_NORMAL_PLANE:
00125     {
00126       //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_NORMAL_PLANE\n", getClassName ().c_str ());
00127       sacmodel_.reset (new SampleConsensusModelNormalPlane<PointT, pcl::Normal> (input_));
00128       break;
00129     }
00130     case SACMODEL_CONE:
00131     {
00132       //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_CONE\n", getClassName ().c_str ());
00133       sacmodel_.reset (new SampleConsensusModelCone<PointT, pcl::Normal> (input_));
00134       break;
00135     }
00136     case SACMODEL_NORMAL_SPHERE:
00137     {
00138       //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_NORMAL_SPHERE\n", getClassName ().c_str ());
00139       sacmodel_.reset (new SampleConsensusModelNormalSphere<PointT, pcl::Normal> (input_));
00140       break;
00141     }
00142     case SACMODEL_NORMAL_PARALLEL_PLANE:
00143     {
00144       //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_NORMAL_PARALLEL_PLANE\n", getClassName ().c_str ());
00145       sacmodel_.reset (new SampleConsensusModelNormalParallelPlane<PointT, pcl::Normal> (input_));
00146       break;
00147     }
00148     case SACMODEL_PARALLEL_PLANE:
00149     {
00150       //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_PARALLEL_PLANE\n", getClassName ().c_str ());
00151       sacmodel_.reset (new SampleConsensusModelParallelPlane<PointT> (input_));
00152       break;
00153     }
00154     default:
00155     {
00156       PCL_ERROR ("[pcl::%s::initSACModel] No valid model given!\n", getClassName ().c_str ());
00157       return (false);
00158     }
00159   }
00160   return (true);
00161 }
00162 
00163 #define PCL_INSTANTIATE_ProjectInliers(T) template class PCL_EXPORTS pcl::ProjectInliers<T>;
00164 
00165 #endif    // PCL_FILTERS_IMPL_PROJECT_INLIERS_H_
00166 


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