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