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_CYLINDER_H_
00039 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CYLINDER_H_
00040
00041 #include <pcl/sample_consensus/sac_model_cylinder.h>
00042 #include <pcl/common/concatenate.h>
00043 #include <unsupported/Eigen/NonLinearOptimization>
00044
00046 template <typename PointT, typename PointNT> bool
00047 pcl::SampleConsensusModelCylinder<PointT, PointNT>::isSampleGood (const std::vector<int> &) const
00048 {
00049 return (true);
00050 }
00051
00053 template <typename PointT, typename PointNT> bool
00054 pcl::SampleConsensusModelCylinder<PointT, PointNT>::computeModelCoefficients (
00055 const std::vector<int> &samples, Eigen::VectorXf &model_coefficients)
00056 {
00057
00058 if (samples.size () != 2)
00059 {
00060 PCL_ERROR ("[pcl::SampleConsensusModelCylinder::computeModelCoefficients] Invalid set of samples given (%zu)!\n", samples.size ());
00061 return (false);
00062 }
00063
00064 if (!normals_)
00065 {
00066 PCL_ERROR ("[pcl::SampleConsensusModelCylinder::computeModelCoefficients] No input dataset containing normals was given!\n");
00067 return (false);
00068 }
00069
00070 Eigen::Vector4f p1 (input_->points[samples[0]].x, input_->points[samples[0]].y, input_->points[samples[0]].z, 0);
00071 Eigen::Vector4f p2 (input_->points[samples[1]].x, input_->points[samples[1]].y, input_->points[samples[1]].z, 0);
00072
00073 Eigen::Vector4f n1 (normals_->points[samples[0]].normal[0], normals_->points[samples[0]].normal[1], normals_->points[samples[0]].normal[2], 0);
00074 Eigen::Vector4f n2 (normals_->points[samples[1]].normal[0], normals_->points[samples[1]].normal[1], normals_->points[samples[1]].normal[2], 0);
00075 Eigen::Vector4f w = n1 + p1 - p2;
00076
00077 float a = n1.dot (n1);
00078 float b = n1.dot (n2);
00079 float c = n2.dot (n2);
00080 float d = n1.dot (w);
00081 float e = n2.dot (w);
00082 float denominator = a*c - b*b;
00083 float sc, tc;
00084
00085 if (denominator < 1e-8)
00086 {
00087 sc = 0.0f;
00088 tc = (b > c ? d / b : e / c);
00089 }
00090 else
00091 {
00092 sc = (b*e - c*d) / denominator;
00093 tc = (a*e - b*d) / denominator;
00094 }
00095
00096
00097 Eigen::Vector4f line_pt = p1 + n1 + sc * n1;
00098 Eigen::Vector4f line_dir = p2 + tc * n2 - line_pt;
00099 line_dir.normalize ();
00100
00101 model_coefficients.resize (7);
00102
00103 model_coefficients[0] = line_pt[0];
00104 model_coefficients[1] = line_pt[1];
00105 model_coefficients[2] = line_pt[2];
00106
00107 model_coefficients[3] = line_dir[0];
00108 model_coefficients[4] = line_dir[1];
00109 model_coefficients[5] = line_dir[2];
00110
00111 model_coefficients[6] = static_cast<float> (sqrt (pcl::sqrPointToLineDistance (p1, line_pt, line_dir)));
00112
00113 if (model_coefficients[6] > radius_max_ || model_coefficients[6] < radius_min_)
00114 return (false);
00115
00116 return (true);
00117 }
00118
00120 template <typename PointT, typename PointNT> void
00121 pcl::SampleConsensusModelCylinder<PointT, PointNT>::getDistancesToModel (
00122 const Eigen::VectorXf &model_coefficients, std::vector<double> &distances)
00123 {
00124
00125 if (!isModelValid (model_coefficients))
00126 {
00127 distances.clear ();
00128 return;
00129 }
00130
00131 distances.resize (indices_->size ());
00132
00133 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00134 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00135 float ptdotdir = line_pt.dot (line_dir);
00136 float dirdotdir = 1.0f / line_dir.dot (line_dir);
00137
00138 for (size_t i = 0; i < indices_->size (); ++i)
00139 {
00140
00141
00142
00143 Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 0);
00144 Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0);
00145
00146 double d_euclid = fabs (pointToLineDistance (pt, model_coefficients) - model_coefficients[6]);
00147
00148
00149 float k = (pt.dot (line_dir) - ptdotdir) * dirdotdir;
00150 Eigen::Vector4f pt_proj = line_pt + k * line_dir;
00151 Eigen::Vector4f dir = pt - pt_proj;
00152 dir.normalize ();
00153
00154
00155 double d_normal = fabs (getAngle3D (n, dir));
00156 d_normal = (std::min) (d_normal, M_PI - d_normal);
00157
00158 distances[i] = fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid);
00159 }
00160 }
00161
00163 template <typename PointT, typename PointNT> void
00164 pcl::SampleConsensusModelCylinder<PointT, PointNT>::selectWithinDistance (
00165 const Eigen::VectorXf &model_coefficients, const double threshold, std::vector<int> &inliers)
00166 {
00167
00168 if (!isModelValid (model_coefficients))
00169 {
00170 inliers.clear ();
00171 return;
00172 }
00173
00174 int nr_p = 0;
00175 inliers.resize (indices_->size ());
00176
00177 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00178 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00179 float ptdotdir = line_pt.dot (line_dir);
00180 float dirdotdir = 1.0f / line_dir.dot (line_dir);
00181
00182 for (size_t i = 0; i < indices_->size (); ++i)
00183 {
00184
00185
00186 Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 0);
00187 Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0);
00188 double d_euclid = fabs (pointToLineDistance (pt, model_coefficients) - model_coefficients[6]);
00189
00190
00191 float k = (pt.dot (line_dir) - ptdotdir) * dirdotdir;
00192 Eigen::Vector4f pt_proj = line_pt + k * line_dir;
00193 Eigen::Vector4f dir = pt - pt_proj;
00194 dir.normalize ();
00195
00196
00197 double d_normal = fabs (getAngle3D (n, dir));
00198 d_normal = (std::min) (d_normal, M_PI - d_normal);
00199
00200 if (fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid) < threshold)
00201 {
00202
00203 inliers[nr_p] = (*indices_)[i];
00204 nr_p++;
00205 }
00206 }
00207 inliers.resize (nr_p);
00208 }
00209
00211 template <typename PointT, typename PointNT> int
00212 pcl::SampleConsensusModelCylinder<PointT, PointNT>::countWithinDistance (
00213 const Eigen::VectorXf &model_coefficients, const double threshold)
00214 {
00215
00216 if (!isModelValid (model_coefficients))
00217 return (0);
00218
00219 int nr_p = 0;
00220
00221 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00222 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00223 float ptdotdir = line_pt.dot (line_dir);
00224 float dirdotdir = 1.0f / line_dir.dot (line_dir);
00225
00226 for (size_t i = 0; i < indices_->size (); ++i)
00227 {
00228
00229
00230 Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 0);
00231 Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0);
00232 double d_euclid = fabs (pointToLineDistance (pt, model_coefficients) - model_coefficients[6]);
00233
00234
00235 float k = (pt.dot (line_dir) - ptdotdir) * dirdotdir;
00236 Eigen::Vector4f pt_proj = line_pt + k * line_dir;
00237 Eigen::Vector4f dir = pt - pt_proj;
00238 dir.normalize ();
00239
00240
00241 double d_normal = fabs (getAngle3D (n, dir));
00242 d_normal = (std::min) (d_normal, M_PI - d_normal);
00243
00244 if (fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid) < threshold)
00245 nr_p++;
00246 }
00247 return (nr_p);
00248 }
00249
00251 template <typename PointT, typename PointNT> void
00252 pcl::SampleConsensusModelCylinder<PointT, PointNT>::optimizeModelCoefficients (
00253 const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)
00254 {
00255 optimized_coefficients = model_coefficients;
00256
00257
00258 if (model_coefficients.size () != 7)
00259 {
00260 PCL_ERROR ("[pcl::SampleConsensusModelCylinder::optimizeModelCoefficients] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00261 return;
00262 }
00263
00264 if (inliers.empty ())
00265 {
00266 PCL_DEBUG ("[pcl::SampleConsensusModelCylinder:optimizeModelCoefficients] Inliers vector empty! Returning the same coefficients.\n");
00267 return;
00268 }
00269
00270 tmp_inliers_ = &inliers;
00271
00272 OptimizationFunctor functor (static_cast<int> (inliers.size ()), this);
00273 Eigen::NumericalDiff<OptimizationFunctor > num_diff (functor);
00274 Eigen::LevenbergMarquardt<Eigen::NumericalDiff<OptimizationFunctor>, float> lm (num_diff);
00275 int info = lm.minimize (optimized_coefficients);
00276
00277
00278 PCL_DEBUG ("[pcl::SampleConsensusModelCylinder::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g %g %g %g \nFinal solution: %g %g %g %g %g %g %g\n",
00279 info, lm.fvec.norm (), model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3],
00280 model_coefficients[4], model_coefficients[5], model_coefficients[6], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2], optimized_coefficients[3], optimized_coefficients[4], optimized_coefficients[5], optimized_coefficients[6]);
00281
00282 Eigen::Vector3f line_dir (optimized_coefficients[3], optimized_coefficients[4], optimized_coefficients[5]);
00283 line_dir.normalize ();
00284 optimized_coefficients[3] = line_dir[0];
00285 optimized_coefficients[4] = line_dir[1];
00286 optimized_coefficients[5] = line_dir[2];
00287 }
00288
00290 template <typename PointT, typename PointNT> void
00291 pcl::SampleConsensusModelCylinder<PointT, PointNT>::projectPoints (
00292 const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool copy_data_fields)
00293 {
00294
00295 if (model_coefficients.size () != 7)
00296 {
00297 PCL_ERROR ("[pcl::SampleConsensusModelCylinder::projectPoints] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00298 return;
00299 }
00300
00301 projected_points.header = input_->header;
00302 projected_points.is_dense = input_->is_dense;
00303
00304 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00305 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00306 float ptdotdir = line_pt.dot (line_dir);
00307 float dirdotdir = 1.0f / line_dir.dot (line_dir);
00308
00309
00310 if (copy_data_fields)
00311 {
00312
00313 projected_points.points.resize (input_->points.size ());
00314 projected_points.width = input_->width;
00315 projected_points.height = input_->height;
00316
00317 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00318
00319 for (size_t i = 0; i < projected_points.points.size (); ++i)
00320
00321 pcl::for_each_type <FieldList> (NdConcatenateFunctor <PointT, PointT> (input_->points[i], projected_points.points[i]));
00322
00323
00324 for (size_t i = 0; i < inliers.size (); ++i)
00325 {
00326 Eigen::Vector4f p (input_->points[inliers[i]].x,
00327 input_->points[inliers[i]].y,
00328 input_->points[inliers[i]].z,
00329 1);
00330
00331 float k = (p.dot (line_dir) - ptdotdir) * dirdotdir;
00332
00333 pcl::Vector4fMap pp = projected_points.points[inliers[i]].getVector4fMap ();
00334 pp = line_pt + k * line_dir;
00335
00336 Eigen::Vector4f dir = p - pp;
00337 dir.normalize ();
00338
00339
00340 pp += dir * model_coefficients[6];
00341 }
00342 }
00343 else
00344 {
00345
00346 projected_points.points.resize (inliers.size ());
00347 projected_points.width = static_cast<uint32_t> (inliers.size ());
00348 projected_points.height = 1;
00349
00350 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00351
00352 for (size_t i = 0; i < inliers.size (); ++i)
00353
00354 pcl::for_each_type <FieldList> (NdConcatenateFunctor <PointT, PointT> (input_->points[inliers[i]], projected_points.points[i]));
00355
00356
00357 for (size_t i = 0; i < inliers.size (); ++i)
00358 {
00359 pcl::Vector4fMap pp = projected_points.points[i].getVector4fMap ();
00360 pcl::Vector4fMapConst p = input_->points[inliers[i]].getVector4fMap ();
00361
00362 float k = (p.dot (line_dir) - ptdotdir) * dirdotdir;
00363
00364 pp = line_pt + k * line_dir;
00365
00366 Eigen::Vector4f dir = p - pp;
00367 dir.normalize ();
00368
00369
00370 pp += dir * model_coefficients[6];
00371 }
00372 }
00373 }
00374
00376 template <typename PointT, typename PointNT> bool
00377 pcl::SampleConsensusModelCylinder<PointT, PointNT>::doSamplesVerifyModel (
00378 const std::set<int> &indices, const Eigen::VectorXf &model_coefficients, const double threshold)
00379 {
00380
00381 if (model_coefficients.size () != 7)
00382 {
00383 PCL_ERROR ("[pcl::SampleConsensusModelCylinder::doSamplesVerifyModel] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00384 return (false);
00385 }
00386
00387 for (std::set<int>::const_iterator it = indices.begin (); it != indices.end (); ++it)
00388 {
00389
00390
00391
00392 Eigen::Vector4f pt (input_->points[*it].x, input_->points[*it].y, input_->points[*it].z, 0);
00393 if (fabs (pointToLineDistance (pt, model_coefficients) - model_coefficients[6]) > threshold)
00394 return (false);
00395 }
00396
00397 return (true);
00398 }
00399
00401 template <typename PointT, typename PointNT> double
00402 pcl::SampleConsensusModelCylinder<PointT, PointNT>::pointToLineDistance (
00403 const Eigen::Vector4f &pt, const Eigen::VectorXf &model_coefficients)
00404 {
00405 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00406 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00407 return sqrt(pcl::sqrPointToLineDistance (pt, line_pt, line_dir));
00408 }
00409
00411 template <typename PointT, typename PointNT> void
00412 pcl::SampleConsensusModelCylinder<PointT, PointNT>::projectPointToCylinder (
00413 const Eigen::Vector4f &pt, const Eigen::VectorXf &model_coefficients, Eigen::Vector4f &pt_proj)
00414 {
00415 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00416 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00417
00418 float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) * line_dir.dot (line_dir);
00419 pt_proj = line_pt + k * line_dir;
00420
00421 Eigen::Vector4f dir = pt - pt_proj;
00422 dir.normalize ();
00423
00424
00425 pt_proj += dir * model_coefficients[6];
00426 }
00427
00429 template <typename PointT, typename PointNT> bool
00430 pcl::SampleConsensusModelCylinder<PointT, PointNT>::isModelValid (const Eigen::VectorXf &model_coefficients)
00431 {
00432
00433 if (model_coefficients.size () != 7)
00434 {
00435 PCL_ERROR ("[pcl::SampleConsensusModelCylinder::isModelValid] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00436 return (false);
00437 }
00438
00439
00440 if (eps_angle_ > 0.0)
00441 {
00442
00443 Eigen::Vector4f coeff;
00444 coeff[0] = model_coefficients[3];
00445 coeff[1] = model_coefficients[4];
00446 coeff[2] = model_coefficients[5];
00447 coeff[3] = 0;
00448
00449 Eigen::Vector4f axis (axis_[0], axis_[1], axis_[2], 0);
00450 double angle_diff = fabs (getAngle3D (axis, coeff));
00451 angle_diff = (std::min) (angle_diff, M_PI - angle_diff);
00452
00453 if (angle_diff > eps_angle_)
00454 return (false);
00455 }
00456
00457 if (radius_min_ != -std::numeric_limits<double>::max() && model_coefficients[6] < radius_min_)
00458 return (false);
00459 if (radius_max_ != std::numeric_limits<double>::max() && model_coefficients[6] > radius_max_)
00460 return (false);
00461
00462 return (true);
00463 }
00464
00465 #define PCL_INSTANTIATE_SampleConsensusModelCylinder(PointT, PointNT) template class PCL_EXPORTS pcl::SampleConsensusModelCylinder<PointT, PointNT>;
00466
00467 #endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CYLINDER_H_
00468