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_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PARALLEL_PLANE_H_
00039 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PARALLEL_PLANE_H_
00040
00041 #include <pcl/sample_consensus/sac_model_normal_parallel_plane.h>
00042
00044 template <typename PointT, typename PointNT> void
00045 pcl::SampleConsensusModelNormalParallelPlane<PointT, PointNT>::selectWithinDistance (
00046 const Eigen::VectorXf &model_coefficients, const double threshold, std::vector<int> &inliers)
00047 {
00048 if (!normals_)
00049 {
00050 PCL_ERROR ("[pcl::SampleConsensusModelNormalParallelPlane::selectWithinDistance] No input dataset containing normals was given!\n");
00051 return;
00052 }
00053
00054
00055 if (!isModelValid (model_coefficients))
00056 {
00057 inliers.clear ();
00058 return;
00059 }
00060
00061
00062 Eigen::Vector4f coeff = model_coefficients;
00063
00064 int nr_p = 0;
00065 inliers.resize (indices_->size ());
00066
00067 for (size_t i = 0; i < indices_->size (); ++i)
00068 {
00069
00070
00071 Eigen::Vector4f p (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 1);
00072 Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0);
00073 double d_euclid = fabs (coeff.dot (p));
00074
00075
00076 double d_normal = getAngle3D (n, coeff);
00077 d_normal = (std::min) (d_normal, fabs(M_PI - d_normal));
00078
00079 if (fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid) < threshold)
00080 {
00081
00082 inliers[nr_p] = (*indices_)[i];
00083 nr_p++;
00084 }
00085 }
00086 inliers.resize (nr_p);
00087 }
00088
00090 template <typename PointT, typename PointNT> int
00091 pcl::SampleConsensusModelNormalParallelPlane<PointT, PointNT>::countWithinDistance (
00092 const Eigen::VectorXf &model_coefficients, const double threshold)
00093 {
00094 if (!normals_)
00095 {
00096 PCL_ERROR ("[pcl::SampleConsensusModelNormalParallelPlane::countWithinDistance] No input dataset containing normals was given!\n");
00097 return (0);
00098 }
00099
00100
00101 if (!isModelValid (model_coefficients))
00102 return (0);
00103
00104
00105 Eigen::Vector4f coeff = model_coefficients;
00106
00107 int nr_p = 0;
00108
00109
00110 for (size_t i = 0; i < indices_->size (); ++i)
00111 {
00112
00113
00114 Eigen::Vector4f p (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 1);
00115 Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0);
00116 double d_euclid = fabs (coeff.dot (p));
00117
00118
00119 double d_normal = fabs (getAngle3D (n, coeff));
00120 d_normal = (std::min) (d_normal, fabs(M_PI - d_normal));
00121
00122 if (fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid) < threshold)
00123 nr_p++;
00124 }
00125 return (nr_p);
00126 }
00127
00128
00130 template <typename PointT, typename PointNT> void
00131 pcl::SampleConsensusModelNormalParallelPlane<PointT, PointNT>::getDistancesToModel (
00132 const Eigen::VectorXf &model_coefficients, std::vector<double> &distances)
00133 {
00134 if (!normals_)
00135 {
00136 PCL_ERROR ("[pcl::SampleConsensusModelNormalParallelPlane::getDistancesToModel] No input dataset containing normals was given!\n");
00137 return;
00138 }
00139
00140
00141 if (!isModelValid (model_coefficients))
00142 {
00143 distances.clear ();
00144 return;
00145 }
00146
00147
00148 Eigen::Vector4f coeff = model_coefficients;
00149
00150 distances.resize (indices_->size ());
00151
00152
00153 for (size_t i = 0; i < indices_->size (); ++i)
00154 {
00155
00156
00157 Eigen::Vector4f p (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 1);
00158 Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0);
00159 double d_euclid = fabs (coeff.dot (p));
00160
00161
00162 double d_normal = getAngle3D (n, coeff);
00163 d_normal = (std::min) (d_normal, fabs (M_PI - d_normal));
00164
00165 distances[i] = fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid);
00166 }
00167 }
00168
00170 template <typename PointT, typename PointNT> bool
00171 pcl::SampleConsensusModelNormalParallelPlane<PointT, PointNT>::isModelValid (const Eigen::VectorXf &model_coefficients)
00172 {
00173
00174 if (model_coefficients.size () != 4)
00175 {
00176 PCL_ERROR ("[pcl::SampleConsensusModelNormalParallelPlane::isModelValid] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00177 return (false);
00178 }
00179
00180
00181 if (eps_angle_ > 0.0)
00182 {
00183
00184 Eigen::Vector4f coeff = model_coefficients;
00185 coeff[3] = 0;
00186 coeff.normalize ();
00187
00188 if (fabs (axis_.dot (coeff)) < cos_angle_)
00189 return (false);
00190 }
00191
00192 if (eps_dist_ > 0.0)
00193 {
00194 if (fabs (-model_coefficients[3] - distance_from_origin_) > eps_dist_)
00195 return (false);
00196 }
00197
00198 return (true);
00199 }
00200
00201 #define PCL_INSTANTIATE_SampleConsensusModelNormalParallelPlane(PointT, PointNT) template class PCL_EXPORTS pcl::SampleConsensusModelNormalParallelPlane<PointT, PointNT>;
00202
00203 #endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PARALLEL_PLANE_H_
00204
00205