Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
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
00056
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
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
00080 switch (model_type)
00081 {
00082 case SACMODEL_PLANE:
00083 {
00084
00085 sacmodel_.reset (new SampleConsensusModelPlane<PointT> (input_));
00086 break;
00087 }
00088 case SACMODEL_LINE:
00089 {
00090
00091 sacmodel_.reset (new SampleConsensusModelLine<PointT> (input_));
00092 break;
00093 }
00094 case SACMODEL_CIRCLE2D:
00095 {
00096
00097 sacmodel_.reset (new SampleConsensusModelCircle2D<PointT> (input_));
00098 break;
00099 }
00100 case SACMODEL_SPHERE:
00101 {
00102
00103 sacmodel_.reset (new SampleConsensusModelSphere<PointT> (input_));
00104 break;
00105 }
00106 case SACMODEL_PARALLEL_LINE:
00107 {
00108
00109 sacmodel_.reset (new SampleConsensusModelParallelLine<PointT> (input_));
00110 break;
00111 }
00112 case SACMODEL_PERPENDICULAR_PLANE:
00113 {
00114
00115 sacmodel_.reset (new SampleConsensusModelPerpendicularPlane<PointT> (input_));
00116 break;
00117 }
00118 case SACMODEL_CYLINDER:
00119 {
00120
00121 sacmodel_.reset (new SampleConsensusModelCylinder<PointT, pcl::Normal> (input_));
00122 break;
00123 }
00124 case SACMODEL_NORMAL_PLANE:
00125 {
00126
00127 sacmodel_.reset (new SampleConsensusModelNormalPlane<PointT, pcl::Normal> (input_));
00128 break;
00129 }
00130 case SACMODEL_CONE:
00131 {
00132
00133 sacmodel_.reset (new SampleConsensusModelCone<PointT, pcl::Normal> (input_));
00134 break;
00135 }
00136 case SACMODEL_NORMAL_SPHERE:
00137 {
00138
00139 sacmodel_.reset (new SampleConsensusModelNormalSphere<PointT, pcl::Normal> (input_));
00140 break;
00141 }
00142 case SACMODEL_NORMAL_PARALLEL_PLANE:
00143 {
00144
00145 sacmodel_.reset (new SampleConsensusModelNormalParallelPlane<PointT, pcl::Normal> (input_));
00146 break;
00147 }
00148 case SACMODEL_PARALLEL_PLANE:
00149 {
00150
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