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 #include <pcl/surface/on_nurbs/fitting_curve_2d.h>
00039 #include <stdexcept>
00040
00041 using namespace pcl;
00042 using namespace on_nurbs;
00043
00044 FittingCurve2d::FittingCurve2d (int order, NurbsDataCurve2d *data)
00045 {
00046 if (order < 2)
00047 throw std::runtime_error ("[NurbsFittingCylinder::NurbsFittingCylinder] Error order to low (order<2).");
00048
00049 ON::Begin ();
00050
00051 m_data = data;
00052 m_nurbs = initNurbsPCA (order, m_data);
00053
00054 in_max_steps = 200;
00055 in_accuracy = 1e-6;
00056 m_quiet = true;
00057 }
00058
00059 FittingCurve2d::FittingCurve2d (NurbsDataCurve2d *data, const ON_NurbsCurve &nc)
00060 {
00061 ON::Begin ();
00062
00063 m_nurbs = ON_NurbsCurve (nc);
00064 m_data = data;
00065
00066 in_max_steps = 200;
00067 in_accuracy = 1e-6;
00068 m_quiet = true;
00069 }
00070
00071 int
00072 FittingCurve2d::findElement (double xi, const std::vector<double> &elements)
00073 {
00074 if (xi >= elements.back ())
00075 return (int (elements.size ()) - 2);
00076
00077 for (unsigned i = 0; i < elements.size () - 1; i++)
00078 {
00079 if (xi >= elements[i] && xi < elements[i + 1])
00080 {
00081 return i;
00082 }
00083 }
00084
00085
00086 return 0;
00087
00088 }
00089
00090 void
00091 FittingCurve2d::refine ()
00092 {
00093 std::vector<double> xi;
00094
00095 std::vector<double> elements = this->getElementVector (m_nurbs);
00096
00097 for (unsigned i = 0; i < elements.size () - 1; i++)
00098 xi.push_back (elements[i] + 0.5 * (elements[i + 1] - elements[i]));
00099
00100 for (unsigned i = 0; i < xi.size (); i++)
00101 m_nurbs.InsertKnot (xi[i], 1);
00102 }
00103
00104 void
00105 FittingCurve2d::refine (double xi)
00106 {
00107 std::vector<double> elements = getElementVector (m_nurbs);
00108
00109 int i = findElement (xi, elements);
00110
00111 double _xi = elements[i] + 0.5 * (elements[i + 1] - elements[i]);
00112 m_nurbs.InsertKnot (_xi, 1);
00113 return;
00114 }
00115
00116 void
00117 FittingCurve2d::assemble (const Parameter ¶meter)
00118 {
00119 int ncp = m_nurbs.m_cv_count;
00120 int nCageReg = m_nurbs.m_cv_count - 2;
00121 int nInt = int (m_data->interior.size ());
00122
00123 double wInt = 1.0;
00124 if (!m_data->interior_weight.empty ())
00125 wInt = m_data->interior_weight[0];
00126
00127 unsigned nrows = nInt + nCageReg;
00128
00129 m_solver.assign (nrows, ncp, 2);
00130
00131 unsigned row (0);
00132
00133 if (wInt > 0.0)
00134 assembleInterior (wInt, parameter.rScale, row);
00135
00136 if (parameter.smoothness > 0.0)
00137 addCageRegularisation (parameter.smoothness, row);
00138
00139 if (row < nrows)
00140 {
00141 m_solver.resize (row);
00142 if (!m_quiet)
00143 printf ("[FittingCurve2d::assemble] Warning: rows do not match: %d %d\n", row, nrows);
00144 }
00145 }
00146 void
00147 FittingCurve2d::addControlPointConstraint (int i, const Eigen::Vector2d &f, double weight)
00148 {
00149 if (i < 0 || i >= m_nurbs.CVCount ())
00150 {
00151 printf ("[FittingCurve2d::addControlPointConstraint] Warning, index out of bounds.\n");
00152 return;
00153 }
00154
00155
00156 unsigned row, cols, dims;
00157 m_solver.getSize (row, cols, dims);
00158 m_solver.resize (row + 1);
00159
00160
00161 m_solver.f (row, 0, f (0) * weight);
00162 m_solver.f (row, 1, f (1) * weight);
00163 for (int j = 0; j < cols; j++)
00164 m_solver.K (row, j, 0.0);
00165 m_solver.K (row, i, weight);
00166 }
00167
00168 double
00169 FittingCurve2d::solve (double damp)
00170 {
00171 double cps_diff (0.0);
00172
00173 if (m_solver.solve ())
00174 cps_diff = updateCurve (damp);
00175
00176 return cps_diff;
00177 }
00178
00179 double
00180 FittingCurve2d::updateCurve (double damp)
00181 {
00182 int ncp = m_nurbs.CVCount ();
00183
00184 double cps_diff (0.0);
00185
00186 for (int j = 0; j < ncp; j++)
00187 {
00188 ON_3dPoint cp_prev;
00189 m_nurbs.GetCV (j, cp_prev);
00190
00191 double x = m_solver.x (j, 0);
00192 double y = m_solver.x (j, 1);
00193
00194 cps_diff += sqrt ((x - cp_prev.x) * (x - cp_prev.x) + (y - cp_prev.y) * (y - cp_prev.y));
00195
00196 ON_3dPoint cp;
00197 cp.x = cp_prev.x + damp * (x - cp_prev.x);
00198 cp.y = cp_prev.y + damp * (y - cp_prev.y);
00199 cp.z = 0.0;
00200
00201 m_nurbs.SetCV (j, cp);
00202 }
00203
00204 return cps_diff / ncp;
00205 }
00206
00207 void
00208 FittingCurve2d::addPointConstraint (const double ¶m, const Eigen::Vector2d &point, double weight, unsigned &row)
00209 {
00210 double *N = new double[m_nurbs.m_order * m_nurbs.m_order];
00211
00212 int E = ON_NurbsSpanIndex (m_nurbs.m_order, m_nurbs.m_cv_count, m_nurbs.m_knot, param, 0, 0);
00213
00214 ON_EvaluateNurbsBasis (m_nurbs.m_order, m_nurbs.m_knot + E, param, N);
00215
00216 m_solver.f (row, 0, point (0) * weight);
00217 m_solver.f (row, 1, point (1) * weight);
00218
00219 for (int i = 0; i < m_nurbs.m_order; i++)
00220 m_solver.K (row, (E + i), weight * N[i]);
00221
00222 row++;
00223
00224 delete[] N;
00225 }
00226
00227 void
00228 FittingCurve2d::addCageRegularisation (double weight, unsigned &row)
00229 {
00230 int ncp = m_nurbs.m_cv_count;
00231
00232 for (int j = 1; j < ncp - 1; j++)
00233 {
00234 m_solver.f (row, 0, 0.0);
00235 m_solver.f (row, 1, 0.0);
00236
00237 m_solver.K (row, (j + 0), -2.0 * weight);
00238 m_solver.K (row, (j - 1), 1.0 * weight);
00239 m_solver.K (row, (j + 1), 1.0 * weight);
00240
00241 row++;
00242 }
00243 }
00244
00245 ON_NurbsCurve
00246 FittingCurve2d::initNurbsCPS (int order, const vector_vec2d &cps)
00247 {
00248 ON_NurbsCurve nurbs;
00249 if (cps.size () < order)
00250 {
00251 printf ("[FittingCurve2d::initCPsNurbsCurve2D] Warning, number of control points too low.\n");
00252 return nurbs;
00253 }
00254
00255 printf ("[FittingCurve2d::initCPsNurbsCurve2D] Warning, this function is under development.\n");
00256
00257
00258
00259
00260
00261
00262
00263
00264
00265
00266
00267
00268
00269
00270
00271
00272
00273
00274
00275
00276
00277
00278 return nurbs;
00279 }
00280
00281 ON_NurbsCurve
00282 FittingCurve2d::initNurbsPCA (int order, NurbsDataCurve2d *data, int ncps)
00283 {
00284 Eigen::Vector2d mean;
00285 Eigen::Matrix2d eigenvectors;
00286 Eigen::Vector2d eigenvalues;
00287
00288 if (ncps < order)
00289 ncps = order;
00290
00291 unsigned s = static_cast<unsigned> (data->interior.size ());
00292 data->interior_param.clear ();
00293
00294 NurbsTools::pca (data->interior, mean, eigenvectors, eigenvalues);
00295
00296 data->mean = mean;
00297 data->eigenvectors = eigenvectors;
00298
00299 eigenvalues = eigenvalues / s;
00300 Eigen::Matrix2d eigenvectors_inv = eigenvectors.inverse ();
00301
00302 Eigen::Vector2d v_max (-DBL_MAX, -DBL_MAX);
00303 Eigen::Vector2d v_min (DBL_MAX, DBL_MAX);
00304 for (unsigned i = 0; i < s; i++)
00305 {
00306 Eigen::Vector2d p (eigenvectors_inv * (data->interior[i] - mean));
00307 data->interior_param.push_back (p (0));
00308
00309 if (p (0) > v_max (0))
00310 v_max (0) = p (0);
00311 if (p (1) > v_max (1))
00312 v_max (1) = p (1);
00313
00314 if (p (0) < v_min (0))
00315 v_min (0) = p (0);
00316 if (p (1) < v_min (1))
00317 v_min (1) = p (1);
00318 }
00319
00320 for (unsigned i = 0; i < s; i++)
00321 {
00322 double &p = data->interior_param[i];
00323 if (v_max (0) > v_min (0))
00324 {
00325 p = (p - v_min (0)) / (v_max (0) - v_min (0));
00326 }
00327 else
00328 {
00329 throw std::runtime_error ("[FittingCurve2d::initNurbsPCABoundingBox] Error: v_max <= v_min");
00330 }
00331 }
00332
00333 ON_NurbsCurve nurbs (2, false, order, ncps);
00334 double delta = 1.0 / (nurbs.KnotCount () - 3);
00335 nurbs.MakeClampedUniformKnotVector (delta);
00336
00337 double dcu = (v_max (0) - v_min (0)) / (ncps - 1);
00338
00339 Eigen::Vector2d cv_t, cv;
00340 for (int i = 0; i < ncps; i++)
00341 {
00342 cv (0) = v_min (0) + dcu * i;
00343 cv (1) = 0.0;
00344 cv_t = eigenvectors * cv + mean;
00345 nurbs.SetCV (i, ON_3dPoint (cv_t (0), cv_t (1), 0.0));
00346 }
00347
00348 return nurbs;
00349 }
00350
00351 void
00352 FittingCurve2d::reverse (ON_NurbsCurve &curve)
00353 {
00354
00355 ON_NurbsCurve curve2 = curve;
00356 for (int i = 0; i < curve.CVCount (); i++)
00357 {
00358 int j = curve.CVCount () - 1 - i;
00359 ON_3dPoint p;
00360 curve.GetCV (i, p);
00361 curve2.SetCV (j, p);
00362 }
00363 curve = curve2;
00364 }
00365
00366 std::vector<double>
00367 FittingCurve2d::getElementVector (const ON_NurbsCurve &nurbs)
00368 {
00369 std::vector<double> result;
00370
00371 int idx_min = 0;
00372 int idx_max = nurbs.m_knot_capacity - 1;
00373 if (nurbs.IsClosed ())
00374 {
00375 idx_min = nurbs.m_order - 2;
00376 idx_max = nurbs.m_knot_capacity - nurbs.m_order + 1;
00377 }
00378
00379 const double* knotsU = nurbs.Knot ();
00380
00381 result.push_back (knotsU[idx_min]);
00382
00383
00384 for (int E = idx_min + 1; E <= idx_max; E++)
00385 {
00386
00387 if (knotsU[E] != knotsU[E - 1])
00388 result.push_back (knotsU[E]);
00389
00390 }
00391
00392 return result;
00393 }
00394
00395 void
00396 FittingCurve2d::assembleInterior (double wInt, double rScale, unsigned &row)
00397 {
00398 int nInt = int (m_data->interior.size ());
00399 m_data->interior_error.clear ();
00400 m_data->interior_normals.clear ();
00401 m_data->interior_line_start.clear ();
00402 m_data->interior_line_end.clear ();
00403
00404 for (int p = 0; p < nInt; p++)
00405 {
00406 Eigen::Vector2d &pcp = m_data->interior[p];
00407
00408
00409 double param;
00410 Eigen::Vector2d pt, t;
00411 double error;
00412 if (p < int (m_data->interior_param.size ()))
00413 {
00414 param = findClosestElementMidPoint (m_nurbs, pcp, m_data->interior_param[p]);
00415 param = inverseMapping (m_nurbs, pcp, param, error, pt, t, rScale, in_max_steps, in_accuracy, m_quiet);
00416 m_data->interior_param[p] = param;
00417 }
00418 else
00419 {
00420 param = findClosestElementMidPoint (m_nurbs, pcp);
00421 param = inverseMapping (m_nurbs, pcp, param, error, pt, t, rScale, in_max_steps, in_accuracy, m_quiet);
00422 m_data->interior_param.push_back (param);
00423 }
00424
00425 m_data->interior_error.push_back (error);
00426
00427 if (p < int (m_data->interior_weight.size ()))
00428 wInt = m_data->interior_weight[p];
00429
00430 m_data->interior_line_start.push_back (pcp);
00431 m_data->interior_line_end.push_back (pt);
00432
00433 addPointConstraint (m_data->interior_param[p], m_data->interior[p], wInt, row);
00434 }
00435 }
00436
00437 double
00438 FittingCurve2d::inverseMapping (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, const double &hint,
00439 double &error, Eigen::Vector2d &p, Eigen::Vector2d &t, double rScale, int maxSteps,
00440 double accuracy, bool quiet)
00441 {
00442 if (nurbs.Order () == 2)
00443 return inverseMappingO2 (nurbs, pt, error, p, t);
00444
00445 double pointAndTangents[4];
00446
00447 double current, delta;
00448 Eigen::Vector2d r;
00449 std::vector<double> elements = getElementVector (nurbs);
00450 double minU = elements[0];
00451 double maxU = elements[elements.size () - 1];
00452
00453 current = hint;
00454
00455 for (int k = 0; k < maxSteps; k++)
00456 {
00457
00458 nurbs.Evaluate (current, 1, 2, pointAndTangents);
00459
00460 p (0) = pointAndTangents[0];
00461 p (1) = pointAndTangents[1];
00462
00463 t (0) = pointAndTangents[2];
00464 t (1) = pointAndTangents[3];
00465
00466 r = p - pt;
00467
00468
00469 int E = findElement (current, elements);
00470 double e = elements[E + 1] - elements[E];
00471
00472 delta = -(0.5 * e * rScale) * r.dot (t) / t.norm ();
00473
00474 if (std::abs (delta) < accuracy)
00475 {
00476
00477 error = r.norm ();
00478 return current;
00479
00480 }
00481 else
00482 {
00483 current = current + delta;
00484
00485 if (current < minU)
00486 current = minU;
00487 if (current > maxU)
00488 current = maxU;
00489 }
00490
00491 }
00492
00493 error = r.norm ();
00494
00495 if (!quiet)
00496 {
00497 printf ("[FittingCurve2d::inverseMapping] Warning: Method did not converge (%e %d).\n", accuracy, maxSteps);
00498 printf ("[FittingCurve2d::inverseMapping] hint: %f current: %f delta: %f error: %f\n", hint, current, delta, error);
00499 }
00500
00501 return current;
00502 }
00503
00504 double
00505 FittingCurve2d::inverseMappingO2 (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double &error,
00506 Eigen::Vector2d &p, Eigen::Vector2d &t)
00507 {
00508 if (nurbs.Order () != 2)
00509 printf ("[FittingCurve2d::inverseMappingO2] Error, order not 2 (polynomial degree 1)\n");
00510
00511 std::vector<double> elements = getElementVector (nurbs);
00512
00513 Eigen::Vector2d min_pt;
00514 double min_param (DBL_MAX);
00515 double min_dist (DBL_MAX);
00516 error = DBL_MAX;
00517 int is_corner (-1);
00518
00519 for (unsigned i = 0; i < elements.size () - 1; i++)
00520 {
00521 Eigen::Vector2d p1;
00522 nurbs.Evaluate (elements[i], 0, 2, &p1 (0));
00523
00524 Eigen::Vector2d p2;
00525 nurbs.Evaluate (elements[i + 1], 0, 2, &p2 (0));
00526
00527 Eigen::Vector2d d1 (p2 (0) - p1 (0), p2 (1) - p1 (1));
00528 Eigen::Vector2d d2 (pt (0) - p1 (0), pt (1) - p1 (1));
00529
00530 double d1_norm = d1.norm ();
00531
00532 double d0_norm = d1.dot (d2) / d1_norm;
00533 Eigen::Vector2d d0 = d1 * d0_norm / d1_norm;
00534 Eigen::Vector2d p0 = p1 + d0;
00535
00536 if (d0_norm < 0.0)
00537 {
00538 double tmp_dist = (p1 - pt).norm ();
00539 if (tmp_dist < min_dist)
00540 {
00541 min_dist = tmp_dist;
00542 min_pt = p1;
00543 min_param = elements[i];
00544 is_corner = i;
00545 }
00546 }
00547 else if (d0_norm >= d1_norm)
00548 {
00549 double tmp_dist = (p2 - pt).norm ();
00550 if (tmp_dist < min_dist)
00551 {
00552 min_dist = tmp_dist;
00553 min_pt = p2;
00554 min_param = elements[i + 1];
00555 is_corner = i + 1;
00556 }
00557 }
00558 else
00559 {
00560 double tmp_dist = (p0 - pt).norm ();
00561 if (tmp_dist < min_dist)
00562 {
00563 min_dist = tmp_dist;
00564 min_pt = p0;
00565 min_param = elements[i] + (d0_norm / d1_norm) * (elements[i + 1] - elements[i]);
00566 is_corner = -1;
00567 }
00568 }
00569 }
00570
00571 if (is_corner >= 0)
00572 {
00573 double param1, param2;
00574 if (is_corner == 0 || is_corner == elements.size () - 1)
00575 {
00576 double x0a = elements[0];
00577 double x0b = elements[elements.size () - 1];
00578 double xa = elements[1];
00579 double xb = elements[elements.size () - 2];
00580
00581 param1 = x0a + 0.5 * (xa - x0a);
00582 param2 = x0b + 0.5 * (xb - x0b);
00583 }
00584 else
00585 {
00586 double x0 = elements[is_corner];
00587 double x1 = elements[is_corner - 1];
00588 double x2 = elements[is_corner + 1];
00589
00590 param1 = x0 + 0.5 * (x1 - x0);
00591 param2 = x0 + 0.5 * (x2 - x0);
00592 }
00593
00594 double pt1[4];
00595 nurbs.Evaluate (param1, 1, 2, pt1);
00596 Eigen::Vector2d t1 (pt1[2], pt1[3]);
00597 t1.normalize ();
00598
00599 double pt2[4];
00600 nurbs.Evaluate (param2, 1, 2, pt2);
00601 Eigen::Vector2d t2 (pt2[2], pt2[3]);
00602 t2.normalize ();
00603
00604 t = 0.5 * (t1 + t2);
00605 }
00606 else
00607 {
00608 double point_tangent[4];
00609 nurbs.Evaluate (min_param, 1, 2, point_tangent);
00610 t (0) = point_tangent[2];
00611 t (1) = point_tangent[3];
00612 }
00613
00614 t.normalize ();
00615 p = min_pt;
00616 return min_param;
00617 }
00618
00619
00620
00621
00622
00623
00624
00625
00626
00627
00628
00629
00630
00631
00632
00633
00634
00635
00636
00637
00638
00639
00640
00641
00642
00643
00644
00645
00646
00647
00648
00649
00650
00651
00652
00653
00654
00655
00656
00657
00658
00659
00660 double
00661 FittingCurve2d::findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double hint)
00662 {
00663
00664 double param = hint;
00665 double points[2];
00666 nurbs.Evaluate (param, 0, 2, points);
00667 Eigen::Vector2d p (points[0], points[1]);
00668 Eigen::Vector2d r = p - pt;
00669
00670 double d_shortest_hint = r.squaredNorm ();
00671 double d_shortest_elem (DBL_MAX);
00672
00673
00674 std::vector<double> elements = pcl::on_nurbs::FittingCurve2d::getElementVector (nurbs);
00675 double seg = 1.0 / (nurbs.Order () - 1);
00676
00677 for (unsigned i = 0; i < elements.size () - 1; i++)
00678 {
00679 double &xi0 = elements[i];
00680 double &xi1 = elements[i + 1];
00681 double dxi = xi1 - xi0;
00682
00683 for (unsigned j = 0; j < nurbs.Order (); j++)
00684 {
00685 double xi = xi0 + (seg * j) * dxi;
00686
00687 nurbs.Evaluate (xi, 0, 2, points);
00688 p (0) = points[0];
00689 p (1) = points[1];
00690
00691 r = p - pt;
00692
00693 double d = r.squaredNorm ();
00694
00695 if (d < d_shortest_elem)
00696 {
00697 d_shortest_elem = d;
00698 param = xi;
00699 }
00700 }
00701 }
00702
00703 if (d_shortest_hint < d_shortest_elem)
00704 return hint;
00705 else
00706 return param;
00707 }
00708
00709 double
00710 FittingCurve2d::findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt)
00711 {
00712 double param (0.0);
00713 Eigen::Vector2d p, r;
00714 std::vector<double> elements = pcl::on_nurbs::FittingCurve2d::getElementVector (nurbs);
00715 double points[2];
00716
00717 double d_shortest (DBL_MAX);
00718 double seg = 1.0 / (nurbs.Order () - 1);
00719
00720 for (unsigned i = 0; i < elements.size () - 1; i++)
00721 {
00722 double &xi0 = elements[i];
00723 double &xi1 = elements[i + 1];
00724 double dxi = xi1 - xi0;
00725
00726 for (unsigned j = 0; j < nurbs.Order (); j++)
00727 {
00728 double xi = xi0 + (seg * j) * dxi;
00729
00730 nurbs.Evaluate (xi, 0, 2, points);
00731 p (0) = points[0];
00732 p (1) = points[1];
00733
00734 r = p - pt;
00735
00736 double d = r.squaredNorm ();
00737
00738 if (d < d_shortest)
00739 {
00740 d_shortest = d;
00741 param = xi;
00742 }
00743 }
00744 }
00745
00746 return param;
00747 }
00748