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