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/distances.h>
00043
00045
00050 template <typename PointT, typename PointNT> void
00051 pcl::SampleConsensusModelCylinder<PointT, PointNT>::getSamples (int &iterations, std::vector<int> &samples)
00052 {
00053
00054 if (indices_->empty ())
00055 {
00056 ROS_ERROR ("[pcl::SampleConsensusModelCylinder::getSamples] Empty set of indices given!");
00057 return;
00058 }
00059
00060 samples.resize (2);
00061 double trand = indices_->size () / (RAND_MAX + 1.0);
00062
00063
00064 if (samples.size () > indices_->size ())
00065 {
00066 ROS_ERROR ("[pcl::SampleConsensusModelCylinder::getSamples] Can not select %zu unique points out of %zu!", samples.size (), indices_->size ());
00067
00068 samples.clear ();
00069 iterations = INT_MAX - 1;
00070 return;
00071 }
00072
00073
00074 int idx = (int)(rand () * trand);
00075
00076 samples[0] = (*indices_)[idx];
00077
00078
00079 do
00080 {
00081 idx = (int)(rand () * trand);
00082 samples[1] = (*indices_)[idx];
00083
00084 } while (samples[1] == samples[0]);
00085
00086 }
00087
00089
00095 template <typename PointT, typename PointNT> bool
00096 pcl::SampleConsensusModelCylinder<PointT, PointNT>::computeModelCoefficients (
00097 const std::vector<int> &samples, Eigen::VectorXf &model_coefficients)
00098 {
00099
00100 if (samples.size () != 2)
00101 {
00102 ROS_ERROR ("[pcl::SampleConsensusModelCylinder::computeModelCoefficients] Invalid set of samples given (%zu)!", samples.size ());
00103 return (false);
00104 }
00105
00106 if (!normals_)
00107 {
00108 ROS_ERROR ("[pcl::SampleConsensusModelCylinder::computeModelCoefficients] No input dataset containing normals was given!");
00109 return (false);
00110 }
00111
00112 Eigen::Vector4f p1 (input_->points[samples[0]].x, input_->points[samples[0]].y, input_->points[samples[0]].z, 0);
00113 Eigen::Vector4f p2 (input_->points[samples[1]].x, input_->points[samples[1]].y, input_->points[samples[1]].z, 0);
00114
00115 Eigen::Vector4f n1 (normals_->points[samples[0]].normal[0], normals_->points[samples[0]].normal[1], normals_->points[samples[0]].normal[2], 0);
00116 Eigen::Vector4f n2 (normals_->points[samples[1]].normal[0], normals_->points[samples[1]].normal[1], normals_->points[samples[1]].normal[2], 0);
00117 Eigen::Vector4f w = n1 + p1 - p2;
00118
00119 double a = n1.dot (n1);
00120 double b = n1.dot (n2);
00121 double c = n2.dot (n2);
00122 double d = n1.dot (w);
00123 double e = n2.dot (w);
00124 double denominator = a*c - b*b;
00125 double sc, tc;
00126
00127 if (denominator < 1e-8)
00128 {
00129 sc = 0.0;
00130 tc = (b > c ? d / b : e / c);
00131 }
00132 else
00133 {
00134 sc = (b*e - c*d) / denominator;
00135 tc = (a*e - b*d) / denominator;
00136 }
00137
00138
00139 Eigen::Vector4f line_pt = p1 + n1 + sc * n1;
00140 Eigen::Vector4f line_dir = p2 + tc * n2 - line_pt;
00141 line_dir.normalize ();
00142
00143 model_coefficients.resize (7);
00144 model_coefficients.template head<3> () = line_pt.template head<3> ();
00145 model_coefficients.template segment<3> (3) = line_dir.template head<3> ();
00146
00147 model_coefficients[6] = sqrt(pcl::sqrPointToLineDistance (p1, line_pt, line_dir));
00148
00149 if (model_coefficients[6] > radius_max_ || model_coefficients[6] < radius_min_)
00150 return (false);
00151
00152 return (true);
00153 }
00154
00156
00160 template <typename PointT, typename PointNT> void
00161 pcl::SampleConsensusModelCylinder<PointT, PointNT>::getDistancesToModel (
00162 const Eigen::VectorXf &model_coefficients, std::vector<double> &distances)
00163 {
00164
00165 if (model_coefficients.size () != 7)
00166 {
00167 ROS_ERROR ("[pcl::SampleConsensusModelCylinder::getDistancesToModel] Invalid number of model coefficients given (%zu)!", model_coefficients.size ());
00168 return;
00169 }
00170
00171
00172 if (!isModelValid (model_coefficients))
00173 {
00174 distances.clear ();
00175 return;
00176 }
00177
00178 distances.resize (indices_->size ());
00179
00180 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00181 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00182 double ptdotdir = line_pt.dot (line_dir);
00183 double dirdotdir = 1.0 / line_dir.dot (line_dir);
00184
00185 for (size_t i = 0; i < indices_->size (); ++i)
00186 {
00187
00188
00189
00190 Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 0);
00191 Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0);
00192
00193 double d_euclid = fabs (pointToLineDistance (pt, model_coefficients) - model_coefficients[6]);
00194
00195
00196 double k = (pt.dot (line_dir) - ptdotdir) * dirdotdir;
00197 Eigen::Vector4f pt_proj = line_pt + k * line_dir;
00198 Eigen::Vector4f dir = pt - pt_proj;
00199 dir.normalize ();
00200
00201
00202 double d_normal = fabs (getAngle3D (n, dir));
00203 d_normal = (std::min) (d_normal, M_PI - d_normal);
00204
00205 distances[i] = fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid);
00206 }
00207 }
00208
00210
00215 template <typename PointT, typename PointNT> void
00216 pcl::SampleConsensusModelCylinder<PointT, PointNT>::selectWithinDistance (
00217 const Eigen::VectorXf &model_coefficients, double threshold, std::vector<int> &inliers)
00218 {
00219
00220 if (model_coefficients.size () != 7)
00221 {
00222 ROS_ERROR ("[pcl::SampleConsensusModelCylinder::selectWithinDistance] Invalid number of model coefficients given (%zu)!", model_coefficients.size ());
00223 return;
00224 }
00225
00226
00227 if (!isModelValid (model_coefficients))
00228 {
00229 inliers.clear ();
00230 return;
00231 }
00232
00233 int nr_p = 0;
00234 inliers.resize (indices_->size ());
00235
00236 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00237 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00238 double ptdotdir = line_pt.dot (line_dir);
00239 double dirdotdir = 1.0 / line_dir.dot (line_dir);
00240
00241 for (size_t i = 0; i < indices_->size (); ++i)
00242 {
00243
00244
00245 Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 0);
00246 Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0);
00247 double d_euclid = fabs (pointToLineDistance (pt, model_coefficients) - model_coefficients[6]);
00248
00249
00250 double k = (pt.dot (line_dir) - ptdotdir) * dirdotdir;
00251 Eigen::Vector4f pt_proj = line_pt + k * line_dir;
00252 Eigen::Vector4f dir = pt - pt_proj;
00253 dir.normalize ();
00254
00255
00256 double d_normal = fabs (getAngle3D (n, dir));
00257 d_normal = (std::min) (d_normal, M_PI - d_normal);
00258
00259 if (fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid) < threshold)
00260 {
00261
00262 inliers[nr_p] = (*indices_)[i];
00263 nr_p++;
00264 }
00265 }
00266 inliers.resize (nr_p);
00267 }
00268
00270
00276 template <typename PointT, typename PointNT> void
00277 pcl::SampleConsensusModelCylinder<PointT, PointNT>::optimizeModelCoefficients (
00278 const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)
00279 {
00280 boost::mutex::scoped_lock lock (tmp_mutex_);
00281
00282 const int n_unknowns = 7;
00283
00284 if (model_coefficients.size () != n_unknowns)
00285 {
00286 ROS_ERROR ("[pcl::SampleConsensusModelCylinder::optimizeModelCoefficients] Invalid number of model coefficients given (%zu)!", model_coefficients.size ());
00287 optimized_coefficients = model_coefficients;
00288 return;
00289 }
00290
00291 if (inliers.empty ())
00292 {
00293 ROS_DEBUG ("[pcl::SampleConsensusModelCylinder:optimizeModelCoefficients] Inliers vector empty! Returning the same coefficients.");
00294 optimized_coefficients = model_coefficients;
00295 return;
00296 }
00297
00298 tmp_inliers_ = &inliers;
00299 int m = inliers.size ();
00300
00301 double *fvec = new double[m];
00302
00303 int iwa[n_unknowns];
00304
00305 int lwa = m * n_unknowns + 5 * n_unknowns + m;
00306 double *wa = new double[lwa];
00307
00308
00309 double x[n_unknowns];
00310 for (int d = 0; d < n_unknowns; ++d)
00311 x[d] = model_coefficients[d];
00312
00313
00314 double tol = sqrt (dpmpar (1));
00315
00316
00317 int info = lmdif1 (&pcl::SampleConsensusModelCylinder<PointT, PointNT>::functionToOptimize, this, m, n_unknowns, x, fvec, tol, iwa, wa, lwa);
00318
00319
00320 ROS_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",
00321 info, enorm (m, fvec), model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3],
00322 model_coefficients[4], model_coefficients[5], model_coefficients[6], x[0], x[1], x[2], x[3], x[4], x[5], x[6]);
00323
00324 optimized_coefficients.resize (n_unknowns);
00325 for (int d = 0; d < n_unknowns; ++d)
00326 optimized_coefficients[d] = x[d];
00327
00328 free (wa); free (fvec);
00329 }
00330
00332
00340 template <typename PointT, typename PointNT> int
00341 pcl::SampleConsensusModelCylinder<PointT, PointNT>::functionToOptimize (void *p, int m, int n, const double *x, double *fvec, int iflag)
00342 {
00343 SampleConsensusModelCylinder *model = (SampleConsensusModelCylinder*)p;
00344
00345 Eigen::Vector4f line_pt (x[0], x[1], x[2], 0);
00346 Eigen::Vector4f line_dir (x[3], x[4], x[5], 0);
00347
00348 for (int i = 0; i < m; ++i)
00349 {
00350
00351 Eigen::Vector4f pt (model->input_->points[(*model->tmp_inliers_)[i]].x,
00352 model->input_->points[(*model->tmp_inliers_)[i]].y,
00353 model->input_->points[(*model->tmp_inliers_)[i]].z, 0);
00354 fvec[i] = pcl::sqrPointToLineDistance (pt, line_pt, line_dir) - x[6]*x[6];
00355 }
00356 return (0);
00357 }
00358
00360
00367 template <typename PointT, typename PointNT> void
00368 pcl::SampleConsensusModelCylinder<PointT, PointNT>::projectPoints (
00369 const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool copy_data_fields)
00370 {
00371
00372 if (model_coefficients.size () != 7)
00373 {
00374 ROS_ERROR ("[pcl::SampleConsensusModelCylinder::projectPoints] Invalid number of model coefficients given (%zu)!", model_coefficients.size ());
00375 return;
00376 }
00377
00378 projected_points.header = input_->header;
00379 projected_points.is_dense = input_->is_dense;
00380
00381 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00382 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00383 double ptdotdir = line_pt.dot (line_dir);
00384 double dirdotdir = 1.0 / line_dir.dot (line_dir);
00385
00386
00387 if (copy_data_fields)
00388 {
00389
00390 projected_points.points.resize (input_->points.size ());
00391 projected_points.width = input_->width;
00392 projected_points.height = input_->height;
00393
00394 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00395
00396 for (size_t i = 0; i < projected_points.points.size (); ++i)
00397
00398 pcl::for_each_type <FieldList> (NdConcatenateFunctor <PointT, PointT> (input_->points[i], projected_points.points[i]));
00399
00400
00401 for (size_t i = 0; i < inliers.size (); ++i)
00402 {
00403 Eigen::Vector4f p (input_->points[inliers[i]].x,
00404 input_->points[inliers[i]].y,
00405 input_->points[inliers[i]].z,
00406 1);
00407
00408 double k = (p.dot (line_dir) - ptdotdir) * dirdotdir;
00409
00410 pcl::Vector4fMap pp = projected_points.points[inliers[i]].getVector4fMap ();
00411 pp = line_pt + k * line_dir;
00412
00413 Eigen::Vector4f dir = p - pp;
00414 dir.normalize ();
00415
00416
00417 pp += dir * model_coefficients[6];
00418 }
00419 }
00420 else
00421 {
00422
00423 projected_points.points.resize (inliers.size ());
00424 projected_points.width = inliers.size ();
00425 projected_points.height = 1;
00426
00427
00428 for (size_t i = 0; i < inliers.size (); ++i)
00429 {
00430 pcl::Vector4fMap pp = projected_points.points[i].getVector4fMap ();
00431 pcl::Vector4fMapConst p = input_->points[inliers[i]].getVector4fMap ();
00432
00433 double k = (p.dot (line_dir) - ptdotdir) * dirdotdir;
00434
00435 pp = line_pt + k * line_dir;
00436
00437 Eigen::Vector4f dir = p - pp;
00438 dir.normalize ();
00439
00440
00441 pp += dir * model_coefficients[6];
00442 }
00443 }
00444 }
00445
00447
00452 template <typename PointT, typename PointNT> bool
00453 pcl::SampleConsensusModelCylinder<PointT, PointNT>::doSamplesVerifyModel (
00454 const std::set<int> &indices, const Eigen::VectorXf &model_coefficients, double threshold)
00455 {
00456
00457 if (model_coefficients.size () != 7)
00458 {
00459 ROS_ERROR ("[pcl::SampleConsensusModelCylinder::doSamplesVerifyModel] Invalid number of model coefficients given (%zu)!", model_coefficients.size ());
00460 return (false);
00461 }
00462
00463 for (std::set<int>::const_iterator it = indices.begin (); it != indices.end (); ++it)
00464 {
00465
00466
00467
00468 Eigen::Vector4f pt (input_->points[*it].x, input_->points[*it].y, input_->points[*it].z, 0);
00469 if (fabs (pointToLineDistance (pt, model_coefficients) - model_coefficients[6]) > threshold)
00470 return (false);
00471 }
00472
00473 return (true);
00474 }
00475
00477
00481 template <typename PointT, typename PointNT> double
00482 pcl::SampleConsensusModelCylinder<PointT, PointNT>::pointToLineDistance (
00483 const Eigen::Vector4f &pt, const Eigen::VectorXf &model_coefficients)
00484 {
00485 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00486 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00487 return sqrt(pcl::sqrPointToLineDistance (pt, line_pt, line_dir));
00488 }
00489
00491
00497 template <typename PointT, typename PointNT> void
00498 pcl::SampleConsensusModelCylinder<PointT, PointNT>::projectPointToCylinder (
00499 const Eigen::Vector4f &pt, const Eigen::VectorXf &model_coefficients, Eigen::Vector4f &pt_proj)
00500 {
00501 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00502 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00503
00504 double k = (pt.dot (line_dir) - line_pt.dot (line_dir)) * line_dir.dot (line_dir);
00505 pt_proj = line_pt + k * line_dir;
00506
00507 Eigen::Vector4f dir = pt - pt_proj;
00508 dir.normalize ();
00509
00510
00511 pt_proj += dir * model_coefficients[6];
00512 }
00513
00515
00518 template <typename PointT, typename PointNT> bool
00519 pcl::SampleConsensusModelCylinder<PointT, PointNT>::isModelValid (const Eigen::VectorXf &model_coefficients)
00520 {
00521
00522 if (model_coefficients.size () != 7)
00523 {
00524 ROS_ERROR ("[pcl::SampleConsensusModelCylinder::isModelValid] Invalid number of model coefficients given (%zu)!", model_coefficients.size ());
00525 return (false);
00526 }
00527
00528
00529 if (eps_angle_ > 0.0)
00530 {
00531
00532 Eigen::Vector4f coeff;
00533 coeff[0] = model_coefficients[3];
00534 coeff[1] = model_coefficients[4];
00535 coeff[2] = model_coefficients[5];
00536 coeff[3] = 0;
00537
00538 Eigen::Vector4f axis (axis_[0], axis_[1], axis_[2], 0);
00539 double angle_diff = fabs (getAngle3D (axis, coeff));
00540 angle_diff = (std::min) (angle_diff, M_PI - angle_diff);
00541
00542 if (angle_diff > eps_angle_)
00543 return (false);
00544 }
00545
00546 if (radius_min_ != -DBL_MAX && model_coefficients[3] < radius_min_)
00547 return (false);
00548 if (radius_max_ != DBL_MAX && model_coefficients[3] > radius_max_)
00549 return (false);
00550
00551 return (true);
00552 }
00553
00554 #define PCL_INSTANTIATE_SampleConsensusModelCylinder(PointT, PointNT) template class pcl::SampleConsensusModelCylinder<PointT, PointNT>;
00555
00556 #endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CYLINDER_H_
00557