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_PLANE_H_
00039 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_PLANE_H_
00040
00041 #include <pcl/sample_consensus/sac_model_plane.h>
00042 #include <pcl/common/centroid.h>
00043 #include <pcl/common/eigen.h>
00044 #include <pcl/common/concatenate.h>
00045
00047 template <typename PointT> bool
00048 pcl::SampleConsensusModelPlane<PointT>::isSampleGood (const std::vector<int> &samples) const
00049 {
00050
00051 if (samples.empty ())
00052 return (false);
00053
00054 pcl::Array4fMapConst p0 = input_->points[samples[0]].getArray4fMap ();
00055 pcl::Array4fMapConst p1 = input_->points[samples[1]].getArray4fMap ();
00056 pcl::Array4fMapConst p2 = input_->points[samples[2]].getArray4fMap ();
00057
00058 Eigen::Array4f dy1dy2 = (p1-p0) / (p2-p0);
00059
00060 return ( (dy1dy2[0] != dy1dy2[1]) || (dy1dy2[2] != dy1dy2[1]) );
00061 }
00062
00064 template <typename PointT> bool
00065 pcl::SampleConsensusModelPlane<PointT>::computeModelCoefficients (
00066 const std::vector<int> &samples, Eigen::VectorXf &model_coefficients)
00067 {
00068
00069 if (samples.size () != 3)
00070 {
00071 PCL_ERROR ("[pcl::SampleConsensusModelPlane::computeModelCoefficients] Invalid set of samples given (%zu)!\n", samples.size ());
00072 return (false);
00073 }
00074
00075 pcl::Array4fMapConst p0 = input_->points[samples[0]].getArray4fMap ();
00076 pcl::Array4fMapConst p1 = input_->points[samples[1]].getArray4fMap ();
00077 pcl::Array4fMapConst p2 = input_->points[samples[2]].getArray4fMap ();
00078
00079
00080 Eigen::Array4f p1p0 = p1 - p0;
00081
00082 Eigen::Array4f p2p0 = p2 - p0;
00083
00084
00085 Eigen::Array4f dy1dy2 = p1p0 / p2p0;
00086 if ( (dy1dy2[0] == dy1dy2[1]) && (dy1dy2[2] == dy1dy2[1]) )
00087 return (false);
00088
00089
00090
00091 model_coefficients.resize (4);
00092 model_coefficients[0] = p1p0[1] * p2p0[2] - p1p0[2] * p2p0[1];
00093 model_coefficients[1] = p1p0[2] * p2p0[0] - p1p0[0] * p2p0[2];
00094 model_coefficients[2] = p1p0[0] * p2p0[1] - p1p0[1] * p2p0[0];
00095 model_coefficients[3] = 0;
00096
00097
00098 model_coefficients.normalize ();
00099
00100
00101 model_coefficients[3] = -1 * (model_coefficients.template head<4>().dot (p0.matrix ()));
00102
00103 return (true);
00104 }
00105
00107 template <typename PointT> void
00108 pcl::SampleConsensusModelPlane<PointT>::getDistancesToModel (
00109 const Eigen::VectorXf &model_coefficients, std::vector<double> &distances)
00110 {
00111
00112 if (model_coefficients.size () != 4)
00113 {
00114 PCL_ERROR ("[pcl::SampleConsensusModelPlane::getDistancesToModel] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00115 return;
00116 }
00117
00118 distances.resize (indices_->size ());
00119
00120
00121 for (size_t i = 0; i < indices_->size (); ++i)
00122 {
00123
00124
00125
00126
00127
00128
00129 Eigen::Vector4f pt (input_->points[(*indices_)[i]].x,
00130 input_->points[(*indices_)[i]].y,
00131 input_->points[(*indices_)[i]].z,
00132 1);
00133 distances[i] = fabs (model_coefficients.dot (pt));
00134 }
00135 }
00136
00138 template <typename PointT> void
00139 pcl::SampleConsensusModelPlane<PointT>::selectWithinDistance (
00140 const Eigen::VectorXf &model_coefficients, const double threshold, std::vector<int> &inliers)
00141 {
00142
00143 if (model_coefficients.size () != 4)
00144 {
00145 PCL_ERROR ("[pcl::SampleConsensusModelPlane::selectWithinDistance] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00146 return;
00147 }
00148
00149 int nr_p = 0;
00150 inliers.resize (indices_->size ());
00151
00152
00153 for (size_t i = 0; i < indices_->size (); ++i)
00154 {
00155
00156
00157 Eigen::Vector4f pt (input_->points[(*indices_)[i]].x,
00158 input_->points[(*indices_)[i]].y,
00159 input_->points[(*indices_)[i]].z,
00160 1);
00161 if (fabs (model_coefficients.dot (pt)) < threshold)
00162 {
00163
00164 inliers[nr_p] = (*indices_)[i];
00165 nr_p++;
00166 }
00167 }
00168 inliers.resize (nr_p);
00169 }
00170
00172 template <typename PointT> int
00173 pcl::SampleConsensusModelPlane<PointT>::countWithinDistance (
00174 const Eigen::VectorXf &model_coefficients, const double threshold)
00175 {
00176
00177 if (model_coefficients.size () != 4)
00178 {
00179 PCL_ERROR ("[pcl::SampleConsensusModelPlane::countWithinDistance] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00180 return (0);
00181 }
00182
00183 int nr_p = 0;
00184
00185
00186 for (size_t i = 0; i < indices_->size (); ++i)
00187 {
00188
00189
00190 Eigen::Vector4f pt (input_->points[(*indices_)[i]].x,
00191 input_->points[(*indices_)[i]].y,
00192 input_->points[(*indices_)[i]].z,
00193 1);
00194 if (fabs (model_coefficients.dot (pt)) < threshold)
00195 nr_p++;
00196 }
00197 return (nr_p);
00198 }
00199
00201 template <typename PointT> void
00202 pcl::SampleConsensusModelPlane<PointT>::optimizeModelCoefficients (
00203 const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)
00204 {
00205
00206 if (model_coefficients.size () != 4)
00207 {
00208 PCL_ERROR ("[pcl::SampleConsensusModelPlane::optimizeModelCoefficients] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00209 optimized_coefficients = model_coefficients;
00210 return;
00211 }
00212
00213
00214 if (inliers.size () < 4)
00215 {
00216 PCL_ERROR ("[pcl::SampleConsensusModelPlane::optimizeModelCoefficients] Not enough inliers found to support a model (%zu)! Returning the same coefficients.\n", inliers.size ());
00217 optimized_coefficients = model_coefficients;
00218 return;
00219 }
00220
00221 Eigen::Vector4f plane_parameters;
00222
00223
00224 EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00225 Eigen::Vector4f xyz_centroid;
00226
00227 computeMeanAndCovarianceMatrix (*input_, inliers, covariance_matrix, xyz_centroid);
00228
00229
00230 EIGEN_ALIGN16 Eigen::Vector3f::Scalar eigen_value;
00231 EIGEN_ALIGN16 Eigen::Vector3f eigen_vector;
00232 pcl::eigen33 (covariance_matrix, eigen_value, eigen_vector);
00233
00234
00235 optimized_coefficients.resize (4);
00236 optimized_coefficients[0] = eigen_vector [0];
00237 optimized_coefficients[1] = eigen_vector [1];
00238 optimized_coefficients[2] = eigen_vector [2];
00239 optimized_coefficients[3] = 0;
00240 optimized_coefficients[3] = -1 * optimized_coefficients.dot (xyz_centroid);
00241 }
00242
00244 template <typename PointT> void
00245 pcl::SampleConsensusModelPlane<PointT>::projectPoints (
00246 const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool copy_data_fields)
00247 {
00248
00249 if (model_coefficients.size () != 4)
00250 {
00251 PCL_ERROR ("[pcl::SampleConsensusModelPlane::projectPoints] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00252 return;
00253 }
00254
00255 projected_points.header = input_->header;
00256 projected_points.is_dense = input_->is_dense;
00257
00258 Eigen::Vector4f mc (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00259
00260
00261 mc.normalize ();
00262
00263 Eigen::Vector4f tmp_mc = model_coefficients;
00264 tmp_mc[0] = mc[0];
00265 tmp_mc[1] = mc[1];
00266 tmp_mc[2] = mc[2];
00267
00268
00269 if (copy_data_fields)
00270 {
00271
00272 projected_points.points.resize (input_->points.size ());
00273 projected_points.width = input_->width;
00274 projected_points.height = input_->height;
00275
00276 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00277
00278 for (size_t i = 0; i < input_->points.size (); ++i)
00279
00280 pcl::for_each_type <FieldList> (NdConcatenateFunctor <PointT, PointT> (input_->points[i], projected_points.points[i]));
00281
00282
00283 for (size_t i = 0; i < inliers.size (); ++i)
00284 {
00285
00286 Eigen::Vector4f p (input_->points[inliers[i]].x,
00287 input_->points[inliers[i]].y,
00288 input_->points[inliers[i]].z,
00289 1);
00290
00291 float distance_to_plane = tmp_mc.dot (p);
00292
00293 pcl::Vector4fMap pp = projected_points.points[inliers[i]].getVector4fMap ();
00294 pp = p - mc * distance_to_plane;
00295 }
00296 }
00297 else
00298 {
00299
00300 projected_points.points.resize (inliers.size ());
00301 projected_points.width = static_cast<uint32_t> (inliers.size ());
00302 projected_points.height = 1;
00303
00304 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00305
00306 for (size_t i = 0; i < inliers.size (); ++i)
00307
00308 pcl::for_each_type <FieldList> (NdConcatenateFunctor <PointT, PointT> (input_->points[inliers[i]], projected_points.points[i]));
00309
00310
00311 for (size_t i = 0; i < inliers.size (); ++i)
00312 {
00313
00314 Eigen::Vector4f p (input_->points[inliers[i]].x,
00315 input_->points[inliers[i]].y,
00316 input_->points[inliers[i]].z,
00317 1);
00318
00319 float distance_to_plane = tmp_mc.dot (p);
00320
00321 pcl::Vector4fMap pp = projected_points.points[i].getVector4fMap ();
00322 pp = p - mc * distance_to_plane;
00323 }
00324 }
00325 }
00326
00328 template <typename PointT> bool
00329 pcl::SampleConsensusModelPlane<PointT>::doSamplesVerifyModel (
00330 const std::set<int> &indices, const Eigen::VectorXf &model_coefficients, const double threshold)
00331 {
00332
00333 if (model_coefficients.size () != 4)
00334 {
00335 PCL_ERROR ("[pcl::SampleConsensusModelPlane::doSamplesVerifyModel] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00336 return (false);
00337 }
00338
00339 for (std::set<int>::const_iterator it = indices.begin (); it != indices.end (); ++it)
00340 {
00341 Eigen::Vector4f pt (input_->points[*it].x,
00342 input_->points[*it].y,
00343 input_->points[*it].z,
00344 1);
00345 if (fabs (model_coefficients.dot (pt)) > threshold)
00346 return (false);
00347 }
00348
00349 return (true);
00350 }
00351
00352 #define PCL_INSTANTIATE_SampleConsensusModelPlane(T) template class PCL_EXPORTS pcl::SampleConsensusModelPlane<T>;
00353
00354 #endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_PLANE_H_
00355