fitting_curve_2d_apdm.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012-, Open Perception, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder(s) nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * 
00035  *
00036  */
00037 
00038 #include <pcl/surface/on_nurbs/fitting_curve_2d_apdm.h>
00039 #include <stdexcept>
00040 
00041 using namespace pcl;
00042 using namespace on_nurbs;
00043 
00044 FittingCurve2dAPDM::FittingCurve2dAPDM (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 = initNurbsCurve2D (order, m_data->interior);
00053 
00054   in_max_steps = 200;
00055   in_accuracy = 1e-6;
00056   m_quiet = true;
00057 }
00058 
00059 FittingCurve2dAPDM::FittingCurve2dAPDM (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 FittingCurve2dAPDM::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   //  xi < elements.front()
00086   return 0;
00087 
00088 }
00089 
00090 void
00091 FittingCurve2dAPDM::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 FittingCurve2dAPDM::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 FittingCurve2dAPDM::fitting (FitParameter &param)
00118 {
00119   double avgerr (DBL_MAX);
00120   double maxerr (DBL_MAX);
00121   bool stop (false);
00122   for (unsigned j = 0; j < param.iterations && !stop; j++)
00123   {
00124     if (2 * m_nurbs.CVCount () < m_data->interior.size ())
00125       if (!(j % param.addCPsIteration))
00126         if (m_nurbs.CVCount () < param.maxCPs)
00127           addCPsOnClosestPointViolation (param.addCPsAccuracy);
00128 
00129     assemble (param.param);
00130 
00131     double cps_diff = solve ();
00132 
00133     if (!m_quiet)
00134       printf ("[FittingCurve2dAPDM::fitting] accuracy: %f / %f\n", cps_diff, param.accuracy);
00135 
00136     if (cps_diff < param.accuracy)
00137       stop = true;
00138   }
00139 }
00140 
00141 void
00142 FittingCurve2dAPDM::assemble (const Parameter &parameter)
00143 {
00144   std::vector<double> elements = getElementVector (m_nurbs);
00145   unsigned cp_res = std::max<unsigned> (1, parameter.closest_point_resolution);
00146 
00147   int cp_red = m_nurbs.m_order - 2;
00148   int ncp = m_nurbs.m_cv_count - 2 * cp_red;
00149   int nCageReg = m_nurbs.m_cv_count - 2 * cp_red;
00150   int nInt = int (m_data->interior.size ());
00151   int nClosestP = int (elements.size ()) * cp_res;
00152 
00153   double wInt = 1.0;
00154   if (!m_data->interior_weight.empty ())
00155   {
00156     wInt = m_data->interior_weight[0];
00157   }
00158 
00159   double wCageReg = parameter.smoothness;
00160 
00161   unsigned nrows = nInt + nClosestP + nCageReg;
00162 
00163   m_solver.assign (nrows, ncp, 2);
00164 
00165   unsigned row (0);
00166 
00167   if (wInt > 0.0)
00168     assembleInterior (wInt, parameter.interior_sigma2, parameter.rScale, row);
00169 
00170   assembleClosestPoints (elements, parameter.closest_point_weight, parameter.closest_point_sigma2, cp_res, row);
00171 
00172   if (wCageReg > 0.0)
00173     addCageRegularisation (wCageReg, row, elements, parameter.smooth_concavity);
00174 
00175   if (row < nrows)
00176   {
00177     m_solver.resize (row);
00178     if (!m_quiet)
00179       printf ("[FittingCurve2dAPDM::assemble] Warning: rows do not match: %d %d\n", row, nrows);
00180   }
00181 }
00182 
00183 double
00184 FittingCurve2dAPDM::solve (double damp)
00185 {
00186   double cps_diff (0.0);
00187 
00188   if (m_solver.solve ())
00189     cps_diff = updateCurve (damp);
00190 
00191   return cps_diff;
00192 }
00193 
00194 double
00195 FittingCurve2dAPDM::updateCurve (double damp)
00196 {
00197   int cp_red = m_nurbs.m_order - 2;
00198   int ncp = m_nurbs.m_cv_count - 2 * cp_red;
00199 
00200   double cps_diff (0.0);
00201   //  double cps_diff_max (0.0);
00202 
00203   for (int j = 0; j < ncp; j++)
00204   {
00205 
00206     ON_3dPoint cp_prev;
00207     m_nurbs.GetCV (j, cp_prev);
00208 
00209     double x = m_solver.x (j, 0);
00210     double y = m_solver.x (j, 1);
00211 
00212     cps_diff += sqrt ((x - cp_prev.x) * (x - cp_prev.x) + (y - cp_prev.y) * (y - cp_prev.y));
00213 
00214     //    if (cps_diff > cps_diff_max)
00215     //      cps_diff_max = cps_diff;
00216 
00217     ON_3dPoint cp;
00218     cp.x = cp_prev.x + damp * (x - cp_prev.x);
00219     cp.y = cp_prev.y + damp * (y - cp_prev.y);
00220     cp.z = 0.0;
00221 
00222     m_nurbs.SetCV (j, cp);
00223 
00224   }
00225 
00226   for (int j = 0; j < 2 * cp_red; j++)
00227   {
00228     ON_3dPoint cp;
00229     m_nurbs.GetCV (2 * cp_red - 1 - j, cp);
00230     m_nurbs.SetCV (m_nurbs.m_cv_count - 1 - j, cp);
00231   }
00232 
00233   return cps_diff / ncp;
00234 }
00235 
00236 void
00237 FittingCurve2dAPDM::addCPsOnClosestPointViolation (double max_error)
00238 {
00239   std::vector<double> elements = getElementVector (m_nurbs);
00240   //  m_data->interior_line_start.clear ();
00241   //  m_data->interior_line_end.clear ();
00242 
00243   int nknots (0);
00244 
00245   for (unsigned i = 0; i < elements.size () - 1; i++)
00246   {
00247 
00248     bool inserted (false);
00249     double dxi = elements[i + 1] - elements[i];
00250 
00251     {
00252       double xi = elements[i];
00253       double points[2];
00254       Eigen::Vector2d p1, p2;
00255       m_nurbs.Evaluate (xi, 0, 2, points);
00256       p1 (0) = points[0];
00257       p1 (1) = points[1];
00258 
00259       unsigned idx = NurbsTools::getClosestPoint (p1, m_data->interior);
00260       p2 = m_data->interior[idx];
00261 
00262       double d = (p2 - p1).squaredNorm ();
00263 
00264       if (d > (max_error * max_error))
00265       {
00266         m_nurbs.InsertKnot (xi + 0.5 * dxi, 1);
00267         //        m_data->interior_line_start.push_back (p2);
00268         //        m_data->interior_line_end.push_back (p1);
00269         nknots++;
00270         inserted = true;
00271       }
00272     }
00273 
00274     if (!inserted)
00275     {
00276       double xi = elements[i] + 0.5 * dxi;
00277       double points[2];
00278       Eigen::Vector2d p1, p2;
00279       m_nurbs.Evaluate (xi, 0, 2, points);
00280       p1 (0) = points[0];
00281       p1 (1) = points[1];
00282 
00283       unsigned idx = NurbsTools::getClosestPoint (p1, m_data->interior);
00284       p2 = m_data->interior[idx];
00285 
00286       double d = (p2 - p1).squaredNorm ();
00287 
00288       if (d > (max_error * max_error))
00289       {
00290         m_nurbs.InsertKnot (xi, 1);
00291         //        m_data->interior_line_start.push_back (p2);
00292         //        m_data->interior_line_end.push_back (p1);
00293         nknots++;
00294       }
00295     }
00296 
00297   }
00298   //  printf("[FittingCurve2dAPDM::addCPsOnClosestPointViolation] %d knots inserted (%d, %d)\n", nknots,
00299   //      m_nurbs.CVCount(), m_nurbs.KnotCount());
00300 }
00301 
00302 ON_NurbsCurve
00303 FittingCurve2dAPDM::removeCPsOnLine (const ON_NurbsCurve &nurbs, double min_curve_th)
00304 {
00305   int cp_red = nurbs.Order () - 2;
00306   int ncp = nurbs.CVCount () - 2 * cp_red;
00307 
00308   std::vector<ON_3dPoint> cps;
00309 
00310   for (int j = 1; j < ncp + 1; j++)
00311   {
00312     ON_3dPoint cp0, cp1, cp2;
00313     nurbs.GetCV ((j + 0) % ncp, cp0);
00314     nurbs.GetCV ((j - 1) % ncp, cp1);
00315     nurbs.GetCV ((j + 1) % ncp, cp2);
00316 
00317     Eigen::Vector3d v1 (cp1.x - cp0.x, cp1.y - cp0.y, cp1.z - cp0.z);
00318     Eigen::Vector3d v2 (cp2.x - cp0.x, cp2.y - cp0.y, cp2.z - cp0.z);
00319     v1.normalize ();
00320     v2.normalize ();
00321 
00322     double d = v1.dot (v2);
00323 
00324     if (d >= min_curve_th)
00325     {
00326       cps.push_back (cp0);
00327     }
00328 
00329   }
00330 
00331   int order = nurbs.Order ();
00332   ON_NurbsCurve nurbs_opt = ON_NurbsCurve (2, false, order, int (cps.size ()) + 2 * cp_red);
00333   nurbs_opt.MakePeriodicUniformKnotVector (1.0 / (double (cps.size ())));
00334   nurbs_opt.m_knot[cp_red] = 0.0;
00335   nurbs_opt.m_knot[nurbs_opt.m_knot_capacity - cp_red - 1] = 1.0;
00336 
00337   for (unsigned j = 0; j < cps.size (); j++)
00338     nurbs_opt.SetCV (j + cp_red, cps[j]);
00339 
00340   for (int j = 0; j < cp_red; j++)
00341   {
00342     ON_3dPoint cp;
00343     nurbs_opt.GetCV (nurbs_opt.m_cv_count - 1 - cp_red + j, cp);
00344     nurbs_opt.SetCV (j, cp);
00345 
00346     nurbs_opt.GetCV (cp_red - j, cp);
00347     nurbs_opt.SetCV (nurbs_opt.m_cv_count - 1 - j, cp);
00348   }
00349 
00350   return nurbs_opt;
00351 
00352   //  NurbsSolve solver;
00353   //  solver.assign(nrows, ncp, 2);
00354   //
00355   //  for (int i = 0; i < ncp; i++) {
00356   //    ON_3dPoint cp;
00357   //    m_nurbs.GetCV(i + cp_red, cp);
00358   //    solver.x(i, 0, cp.x);
00359   //    solver.x(i, 1, cp.y);
00360   //  }
00361   //
00362   //  // addCageRegularisation
00363   //  int row(0);
00364   //  {
00365   //    solver.f(row, 0, 0.0);
00366   //    solver.f(row, 1, 0.0);
00367   //    for (int j = 1; j < ncp + 1; j++) {
00368   //      solver.K(row, (j + 0) % ncp, -2.0);
00369   //      solver.K(row, (j - 1) % ncp, 1.0);
00370   //      solver.K(row, (j + 1) % ncp, 1.0);
00371   //      row++;
00372   //    }
00373   //  }
00374   //
00375   //  Eigen::MatrixXd d = solver.diff();
00376   //
00377   //  for (int i = 0; i < ncp; i++) {
00378   //    double dn = d.row(i).norm();
00379   //    printf("[FittingCurve2dAPDM::optimize] error: %f\n", dn);
00380   //    if (dn > max_curve_th)
00381   //      dbgWin.AddPoint3D(solver.x(i, 0), solver.x(i, 1), 0.0, 0, 0, 255, 10);
00382   //    if (dn < min_curve_th)
00383   //      dbgWin.AddPoint3D(solver.x(i, 0), solver.x(i, 1), 0.0, 255, 0, 0, 10);
00384   //  }
00385 }
00386 
00387 void
00388 FittingCurve2dAPDM::addPointConstraint (const double &param, const Eigen::Vector2d &point, double weight, unsigned &row)
00389 {
00390   int cp_red = m_nurbs.m_order - 2;
00391   int ncp = m_nurbs.m_cv_count - 2 * cp_red;
00392   double *N = new double[m_nurbs.m_order * m_nurbs.m_order];
00393 
00394   int E = ON_NurbsSpanIndex (m_nurbs.m_order, m_nurbs.m_cv_count, m_nurbs.m_knot, param, 0, 0);
00395 
00396   ON_EvaluateNurbsBasis (m_nurbs.m_order, m_nurbs.m_knot + E, param, N);
00397 
00398   m_solver.f (row, 0, point (0) * weight);
00399   m_solver.f (row, 1, point (1) * weight);
00400 
00401   for (int i = 0; i < m_nurbs.m_order; i++)
00402     m_solver.K (row, (E + i) % ncp, weight * N[i]);
00403 
00404   row++;
00405 
00406   delete[] N;
00407 }
00408 
00409 void
00410 FittingCurve2dAPDM::addCageRegularisation (double weight, unsigned &row, const std::vector<double> &elements,
00411                                            double wConcav)
00412 {
00413   int cp_red = (m_nurbs.m_order - 2);
00414   int ncp = (m_nurbs.m_cv_count - 2 * cp_red);
00415 
00416   //  m_data->interior_line_start.clear();
00417   //  m_data->interior_line_end.clear();
00418   for (int j = 1; j < ncp + 1; j++)
00419   {
00420 
00421     if (wConcav == 0.0)
00422     {
00423       m_solver.f (row, 0, 0.0);
00424       m_solver.f (row, 1, 0.0);
00425     }
00426     else
00427     {
00428       int i = j % ncp;
00429 
00430       if (i >= int (m_data->closest_points_error.size () - 1))
00431       {
00432         printf ("[FittingCurve2dAPDM::addCageRegularisation] Warning, index for closest_points_error out of bounds\n");
00433         m_solver.f (row, 0, 0.0);
00434         m_solver.f (row, 1, 0.0);
00435       }
00436       else
00437       {
00438         Eigen::Vector2d t, n;
00439         double pt[4];
00440 
00441         double xi = elements[i] + 0.5 * (elements[i + 1] - elements[i]);
00442         m_nurbs.Evaluate (xi, 1, 2, pt);
00443         t (0) = pt[2];
00444         t (1) = pt[3];
00445         n (0) = -t (1);
00446         n (1) = t (0);
00447         n.normalize ();
00448 
00449         double err = m_data->closest_points_error[i] + 0.5 * (m_data->closest_points_error[i + 1]
00450             - m_data->closest_points_error[i]);
00451         m_solver.f (row, 0, err * wConcav * n (0));
00452         m_solver.f (row, 1, err * wConcav * n (1));
00453 
00454         Eigen::Vector2d p1, p2;
00455         p1 (0) = pt[0];
00456         p1 (1) = pt[1];
00457         p2 = p1 + n * wConcav * err;
00458         //        m_data->interior_line_start.push_back(p1);
00459         //        m_data->interior_line_end.push_back(p2);
00460       }
00461     }
00462 
00463     m_solver.K (row, (j + 0) % ncp, -2.0 * weight);
00464     m_solver.K (row, (j - 1) % ncp, 1.0 * weight);
00465     m_solver.K (row, (j + 1) % ncp, 1.0 * weight);
00466 
00467     row++;
00468   }
00469 }
00470 
00471 //ON_NurbsCurve
00472 //FittingCurve2dAPDM::initCPsNurbsCurve2D (int order, const vector_vec2d &cps)
00473 //{
00474 //  ON_NurbsCurve nurbs;
00475 //  if ((int)cps.size () < (2 * order))
00476 //  {
00477 //    printf ("[FittingCurve2dAPDM::initCPsNurbsCurve2D] Warning, number of control points too low.\n");
00478 //    return nurbs;
00479 //  }
00480 //
00481 //  int cp_red = order - 2;
00482 //  int ncps = cps.size () + cp_red;
00483 //  nurbs = ON_NurbsCurve (2, false, order, ncps);
00484 //  nurbs.MakePeriodicUniformKnotVector (1.0 / (ncps - order + 1));
00485 //
00486 //  for (int j = 0; j < ncps; j++)
00487 //    nurbs.SetCV (j, ON_3dPoint (cps[j] (0), cps[j] (1), 0.0));
00488 //
00489 //  for (int j = 0; j < cp_red; j++)
00490 //  {
00491 //    ON_3dPoint cp;
00492 //    nurbs.GetCV (nurbs.m_cv_count - 1 - cp_red + j, cp);
00493 //    nurbs.SetCV (j, cp);
00494 //
00495 //    nurbs.GetCV (cp_red - j, cp);
00496 //    nurbs.SetCV (nurbs.m_cv_count - 1 - j, cp);
00497 //  }
00498 //
00499 //  return nurbs;
00500 //} // commented 6.6.2012 (thomas.moerwald)
00501 // reason: B-Splines are not closed properly
00502 
00503 ON_NurbsCurve
00504 FittingCurve2dAPDM::initCPsNurbsCurve2D (int order, const vector_vec2d &cps)
00505 {
00506   int cp_red = order - 2;
00507   ON_NurbsCurve nurbs;
00508   if (cps.size () < 3 || cps.size () < (2 * cp_red + 1))
00509   {
00510     printf ("[FittingCurve2dAPDM::initCPsNurbsCurve2D] Warning, number of control points too low.\n");
00511     return nurbs;
00512   }
00513 
00514   int ncps = int (cps.size ()) + 2 * cp_red; // +2*cp_red for smoothness and +1 for closing
00515   nurbs = ON_NurbsCurve (2, false, order, ncps);
00516   nurbs.MakePeriodicUniformKnotVector (1.0 / (ncps - order + 1));
00517 
00518   for (int j = 0; j < cps.size (); j++)
00519     nurbs.SetCV (cp_red + j, ON_3dPoint (cps[j] (0), cps[j] (1), 0.0));
00520 
00521   // close nurbs
00522   nurbs.SetCV (cp_red + int (cps.size ()), ON_3dPoint (cps[0] (0), cps[0] (1), 0.0));
00523 
00524   // make smooth at closing point
00525   for (int j = 0; j < cp_red; j++)
00526   {
00527     ON_3dPoint cp;
00528     nurbs.GetCV (nurbs.CVCount () - 1 - cp_red + j, cp);
00529     nurbs.SetCV (j, cp);
00530 
00531     nurbs.GetCV (cp_red - j, cp);
00532     nurbs.SetCV (nurbs.CVCount () - 1 - j, cp);
00533   }
00534 
00535   return nurbs;
00536 }
00537 
00538 ON_NurbsCurve
00539 FittingCurve2dAPDM::initNurbsCurve2D (int order, const vector_vec2d &data, int ncps, double radiusF)
00540 {
00541   if (data.empty ())
00542     printf ("[FittingCurve2dAPDM::initNurbsCurve2D] Warning, no boundary parameters available\n");
00543 
00544   Eigen::Vector2d mean = NurbsTools::computeMean (data);
00545 
00546   unsigned s = unsigned (data.size ());
00547 
00548   double r (0.0);
00549   for (unsigned i = 0; i < s; i++)
00550   {
00551     Eigen::Vector2d d = data[i] - mean;
00552     double sn = d.squaredNorm ();
00553     if (sn > r)
00554       r = sn;
00555   }
00556   r = radiusF * sqrt (r);
00557 
00558   if (ncps < 2 * order)
00559     ncps = 2 * order;
00560 
00561   ON_NurbsCurve nurbs = ON_NurbsCurve (2, false, order, ncps);
00562   nurbs.MakePeriodicUniformKnotVector (1.0 / (ncps - order + 1));
00563 
00564   double dcv = (2.0 * M_PI) / (ncps - order + 1);
00565   Eigen::Vector2d cv;
00566   for (int j = 0; j < ncps; j++)
00567   {
00568     cv (0) = r * sin (dcv * j);
00569     cv (1) = r * cos (dcv * j);
00570     cv = cv + mean;
00571     nurbs.SetCV (j, ON_3dPoint (cv (0), cv (1), 0.0));
00572   }
00573 
00574   return nurbs;
00575 }
00576 
00577 //ON_NurbsCurve FittingCurve2dAPDM::initNurbsCurvePCA(int order, const vector_vec2d &data)
00578 //{
00579 //  if (data.empty())
00580 //    printf("[FittingCurve2dAPDM::initNurbsCurvePCA] Warning, no boundary parameters available\n");
00581 //
00582 //  Eigen::Vector3d mean;
00583 //  Eigen::Matrix3d eigenvectors;
00584 //  Eigen::Vector3d eigenvalues;
00585 //
00586 //  unsigned s = data.size();
00587 //
00588 //  NurbsTools::pca(data, mean, eigenvectors, eigenvalues);
00589 //
00590 //  eigenvalues = eigenvalues / s; // seems that the eigenvalues are dependent on the number of points (???)
00591 //
00592 //  double r = 2.0 * sqrt(eigenvalues(0));
00593 //
00594 //  int ncpsV(2 * order);
00595 //  ON_NurbsCurve nurbs = ON_NurbsCurve(3, false, order, ncpsV);
00596 //  nurbs.MakePeriodicUniformKnotVector(1.0 / (ncpsV - order + 1));
00597 //
00598 //  double dcv = (2.0 * M_PI) / (ncpsV - order + 1);
00599 //  Eigen::Vector3d cv, cv_t;
00600 //  for (int j = 0; j < ncpsV; j++) {
00601 //    cv(0) = r * sin(dcv * j);
00602 //    cv(1) = r * cos(dcv * j);
00603 //    cv(2) = 0.0;
00604 //    cv_t = eigenvectors * cv + mean;
00605 //    nurbs.SetCV(j, ON_3dPoint(cv_t(0), cv_t(1), cv_t(2)));
00606 //  }
00607 //
00608 //  return nurbs;
00609 //}
00610 
00611 std::vector<double>
00612 FittingCurve2dAPDM::getElementVector (const ON_NurbsCurve &nurbs)
00613 {
00614   std::vector<double> result;
00615 
00616   int idx_min = 0;
00617   int idx_max = nurbs.m_knot_capacity - 1;
00618   if (nurbs.IsClosed ())
00619   {
00620     idx_min = nurbs.m_order - 2;
00621     idx_max = nurbs.m_knot_capacity - nurbs.m_order + 1;
00622   }
00623 
00624   const double* knotsU = nurbs.Knot ();
00625 
00626   result.push_back (knotsU[idx_min]);
00627 
00628   //for(int E=(m_nurbs.m_order[0]-2); E<(m_nurbs.m_knot_capacity[0]-m_nurbs.m_order[0]+2); E++) {
00629   for (int E = idx_min + 1; E <= idx_max; E++)
00630   {
00631 
00632     if (knotsU[E] != knotsU[E - 1]) // do not count double knots
00633       result.push_back (knotsU[E]);
00634 
00635   }
00636 
00637   return result;
00638 }
00639 
00640 void
00641 FittingCurve2dAPDM::assembleInterior (double wInt, double sigma2, double rScale, unsigned &row)
00642 {
00643   int nInt = int (m_data->interior.size ());
00644   bool wFunction (true);
00645   double ds = 1.0 / (2.0 * sigma2);
00646   m_data->interior_error.clear ();
00647   m_data->interior_normals.clear ();
00648   m_data->interior_line_start.clear ();
00649   m_data->interior_line_end.clear ();
00650 
00651   for (int p = 0; p < nInt; p++)
00652   {
00653     Eigen::Vector2d &pcp = m_data->interior[p];
00654 
00655     // inverse mapping
00656     double param;
00657     Eigen::Vector2d pt, t;
00658     double error;
00659     if (p < int (m_data->interior_param.size ()))
00660     {
00661       param = findClosestElementMidPoint (m_nurbs, pcp, m_data->interior_param[p]);
00662       param = inverseMapping (m_nurbs, pcp, param, error, pt, t, rScale, in_max_steps, in_accuracy, m_quiet);
00663       m_data->interior_param[p] = param;
00664     }
00665     else
00666     {
00667       param = findClosestElementMidPoint (m_nurbs, pcp);
00668       param = inverseMapping (m_nurbs, pcp, param, error, pt, t, rScale, in_max_steps, in_accuracy, m_quiet);
00669       m_data->interior_param.push_back (param);
00670     }
00671 
00672     m_data->interior_error.push_back (error);
00673 
00674     // evaluate if point lies inside or outside the closed curve
00675     Eigen::Vector3d a (pcp (0) - pt (0), pcp (1) - pt (1), 0.0);
00676     Eigen::Vector3d b (t (0), t (1), 0.0);
00677     Eigen::Vector3d z = a.cross (b);
00678 
00679     if (p < int (m_data->interior_weight.size ()))
00680       wInt = m_data->interior_weight[p];
00681 
00682     if (p < int (m_data->interior_weight_function.size ()))
00683       wFunction = m_data->interior_weight_function[p];
00684 
00685     double w (wInt);
00686     if (z (2) > 0.0 && wFunction)
00687     {
00688       w = wInt * exp (-(error * error) * ds);
00689     }
00690 
00691     {
00692       m_data->interior_line_start.push_back (pcp);
00693       m_data->interior_line_end.push_back (pt);
00694     }
00695 
00696     //      w = 0.5 * wInt * exp(-(error * error) * ds);
00697 
00698     // evaluate if this point is the closest point
00699     //    int idx = NurbsTools::getClosestPoint(pt, m_data->interior);
00700     //    if(idx == p)
00701     //      w = 2.0 * wInt;
00702 
00703     if (w > 1e-6) // avoids ill-conditioned matrix
00704       addPointConstraint (m_data->interior_param[p], m_data->interior[p], w, row);
00705     else
00706     {
00707       //      m_solver.K(row, 0, 0.0);
00708       //      row++;
00709     }
00710   }
00711 }
00712 
00713 //void FittingCurve2dAPDM::assembleCommon(double wCommon, unsigned &row)
00714 //{
00715 //  int nCommon = m_data->common.size();
00716 //  for (int p = 0; p < nCommon; p++) {
00717 //    Eigen::Vector2d &pcp = m_data->common[p];
00718 //
00719 //    // inverse mapping
00720 //    double param;
00721 //    Eigen::Vector2d pt, t;
00722 //    double error;
00723 //    if (p < (int) m_data->common_param.size()) {
00724 //      param = inverseMapping(m_nurbs, pcp, m_data->common_param[p], error, pt, t, in_max_steps, in_accuracy);
00725 //      m_data->common_param[p] = param;
00726 //    } else {
00727 //      param = inverseMapping(m_nurbs, pcp, (double*) NULL, error, pt, t, in_max_steps, in_accuracy);
00728 //      m_data->common_param.push_back(param);
00729 //    }
00730 //
00731 //    addPointConstraint(m_data->common_param[p], pcp, wCommon, row);
00732 //  }
00733 //}
00734 
00735 void
00736 FittingCurve2dAPDM::assembleClosestPoints (const std::vector<double> &elements, double weight, double sigma2,
00737                                            unsigned samples_per_element, unsigned &row)
00738 {
00739   m_data->closest_points.clear ();
00740   m_data->closest_points_param.clear ();
00741   m_data->closest_points_error.clear ();
00742   //  m_data->interior_line_start.clear();
00743   //  m_data->interior_line_end.clear();
00744 
00745   if (samples_per_element <= 0)
00746     samples_per_element = 1;
00747 
00748   double ds = 1.0 / (2.0 * sigma2);
00749   double seg = 1.0 / (samples_per_element + 1);
00750 
00751   for (unsigned i = 0; i < elements.size (); i++)
00752   {
00753     int k = i % int (elements.size ());
00754     double xi0 = elements[i];
00755     double dxi = elements[k] - xi0;
00756 
00757     for (unsigned j = 0; j < samples_per_element; j++)
00758     {
00759       double xi = xi0 + (seg * (j + 1)) * dxi;
00760 
00761       double points[4];
00762       Eigen::Vector2d p1, p2, p3, t, in;
00763       m_nurbs.Evaluate (xi, 1, 2, points);
00764       p1 (0) = points[0];
00765       p1 (1) = points[1];
00766       t (0) = points[2];
00767       t (1) = points[3];
00768       in (0) = t (1);
00769       in (1) = -t (0);
00770       in.normalize ();
00771 
00772       unsigned idxcp;
00773       unsigned idx = NurbsTools::getClosestPoint (p1, in, m_data->interior, idxcp);
00774       p2 = m_data->interior[idx];
00775       p3 = m_data->interior[idxcp];
00776 
00777       //    double xi2 = m_data->interior_param[idx];
00778 
00779       double error2_2 = (p2 - p1).squaredNorm ();
00780       double error2_3 = (p3 - p1).squaredNorm ();
00781 
00782       m_data->closest_points.push_back (p3);
00783       m_data->closest_points_param.push_back (xi);
00784       m_data->closest_points_error.push_back (error2_3);
00785 
00786       double w (weight);
00787       w = 0.5 * weight * exp (-(error2_2) * ds);
00788       //    w = weight * std::fabs(in.dot(p2-p1));
00789 
00790       //    if (weight > 0.0 && (std::fabs(xi2 - xi) < std::fabs(dxi)))
00791       if (w > 0.0)
00792       {
00793         addPointConstraint (xi, p2, w, row);
00794         //      m_data->interior_line_start.push_back(p1);
00795         //      m_data->interior_line_end.push_back(p2);
00796       }
00797     }
00798   }
00799 }
00800 
00801 double
00802 FittingCurve2dAPDM::inverseMapping (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, const double &hint,
00803                                     double &error, Eigen::Vector2d &p, Eigen::Vector2d &t, double rScale, int maxSteps,
00804                                     double accuracy, bool quiet)
00805 {
00806   if (nurbs.Order () == 2)
00807     return inverseMappingO2 (nurbs, pt, error, p, t);
00808 
00809   //int cp_red = (nurbs.m_order - 2);
00810   //int ncpj = (int (nurbs.m_cv_count) - 2 * cp_red);
00811   double pointAndTangents[4];
00812 
00813   double current, delta;
00814   Eigen::Vector2d r;
00815   std::vector<double> elements = getElementVector (nurbs);
00816   double minU = elements[0];
00817   double maxU = elements[elements.size () - 1];
00818 
00819   current = hint;
00820 
00821   for (int k = 0; k < maxSteps; k++)
00822   {
00823 
00824     nurbs.Evaluate (current, 1, 2, pointAndTangents);
00825 
00826     p (0) = pointAndTangents[0];
00827     p (1) = pointAndTangents[1];
00828 
00829     t (0) = pointAndTangents[2];
00830     t (1) = pointAndTangents[3];
00831 
00832     r = p - pt;
00833 
00834     // step width control
00835     int E = findElement (current, elements);
00836     double e = elements[E + 1] - elements[E];
00837 
00838     delta = -(0.5 * e * rScale) * r.dot (t) / t.norm (); //  A.ldlt().solve(b);
00839 
00840     //    e = 0.5 * std::abs<double> (e);
00841     //    if (delta > e)
00842     //      delta = e;
00843     //    if (delta < -e)
00844     //      delta = -e;
00845 
00846     if (std::abs (delta) < accuracy)
00847     {
00848 
00849       error = r.norm ();
00850       return current;
00851 
00852     }
00853     else
00854     {
00855       current = current + delta;
00856 
00857       if (current < minU)
00858         current = maxU - (minU - current);
00859       else if (current > maxU)
00860         current = minU + (current - maxU);
00861 
00862     }
00863 
00864   }
00865 
00866   error = r.norm ();
00867 
00868   if (!quiet)
00869   {
00870     printf ("[FittingCurve2dAPDM::inverseMapping] Warning: Method did not converge (%e %d).\n", accuracy, maxSteps);
00871     printf ("[FittingCurve2dAPDM::inverseMapping] hint: %f current: %f delta: %f error: %f\n", hint, current, delta,
00872             error);
00873   }
00874 
00875   return current;
00876 }
00877 
00878 double
00879 FittingCurve2dAPDM::inverseMappingO2 (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double &error,
00880                                       Eigen::Vector2d &p, Eigen::Vector2d &t)
00881 {
00882   if (nurbs.Order () != 2)
00883     printf ("[FittingCurve2dAPDM::inverseMappingO2] Error, order not 2 (polynomial degree 1)\n");
00884 
00885   std::vector<double> elements = getElementVector (nurbs);
00886 
00887   Eigen::Vector2d min_pt;
00888   double min_param (DBL_MAX);
00889   double min_dist (DBL_MAX);
00890   error = DBL_MAX;
00891   int is_corner (-1);
00892 
00893   for (unsigned i = 0; i < elements.size () - 1; i++)
00894   {
00895     Eigen::Vector2d p1;
00896     nurbs.Evaluate (elements[i], 0, 2, &p1 (0));
00897 
00898     Eigen::Vector2d p2;
00899     nurbs.Evaluate (elements[i + 1], 0, 2, &p2 (0));
00900 
00901     Eigen::Vector2d d1 (p2 (0) - p1 (0), p2 (1) - p1 (1));
00902     Eigen::Vector2d d2 (pt (0) - p1 (0), pt (1) - p1 (1));
00903 
00904     double d1_norm = d1.norm ();
00905 
00906     double d0_norm = d1.dot (d2) / d1_norm;
00907     Eigen::Vector2d d0 = d1 * d0_norm / d1_norm;
00908     Eigen::Vector2d p0 = p1 + d0;
00909 
00910     if (d0_norm < 0.0)
00911     {
00912       double tmp_dist = (p1 - pt).norm ();
00913       if (tmp_dist < min_dist)
00914       {
00915         min_dist = tmp_dist;
00916         min_pt = p1;
00917         min_param = elements[i];
00918         is_corner = i;
00919       }
00920     }
00921     else if (d0_norm >= d1_norm)
00922     {
00923       double tmp_dist = (p2 - pt).norm ();
00924       if (tmp_dist < min_dist)
00925       {
00926         min_dist = tmp_dist;
00927         min_pt = p2;
00928         min_param = elements[i + 1];
00929         is_corner = i + 1;
00930       }
00931     }
00932     else
00933     { // p0 lies on line segment
00934       double tmp_dist = (p0 - pt).norm ();
00935       if (tmp_dist < min_dist)
00936       {
00937         min_dist = tmp_dist;
00938         min_pt = p0;
00939         min_param = elements[i] + (d0_norm / d1_norm) * (elements[i + 1] - elements[i]);
00940         is_corner = -1;
00941       }
00942     }
00943   }
00944 
00945   if (is_corner >= 0)
00946   {
00947     double param1, param2;
00948     if (is_corner == 0 || is_corner == elements.size () - 1)
00949     {
00950       double x0a = elements[0];
00951       double x0b = elements[elements.size () - 1];
00952       double xa = elements[1];
00953       double xb = elements[elements.size () - 2];
00954 
00955       param1 = x0a + 0.5 * (xa - x0a);
00956       param2 = x0b + 0.5 * (xb - x0b);
00957     }
00958     else
00959     {
00960       double x0 = elements[is_corner];
00961       double x1 = elements[is_corner - 1];
00962       double x2 = elements[is_corner + 1];
00963 
00964       param1 = x0 + 0.5 * (x1 - x0);
00965       param2 = x0 + 0.5 * (x2 - x0);
00966     }
00967 
00968     double pt1[4];
00969     nurbs.Evaluate (param1, 1, 2, pt1);
00970     Eigen::Vector2d t1 (pt1[2], pt1[3]);
00971     t1.normalize ();
00972 
00973     double pt2[4];
00974     nurbs.Evaluate (param2, 1, 2, pt2);
00975     Eigen::Vector2d t2 (pt2[2], pt2[3]);
00976     t2.normalize ();
00977 
00978     t = 0.5 * (t1 + t2);
00979   }
00980   else
00981   {
00982     double point_tangent[4];
00983     nurbs.Evaluate (min_param, 1, 2, point_tangent);
00984     t (0) = point_tangent[2];
00985     t (1) = point_tangent[3];
00986   }
00987 
00988   t.normalize ();
00989   p = min_pt;
00990   return min_param;
00991 }
00992 
00993 //double
00994 //FittingCurve2dAPDM::inverseMapping (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double* phint, double &error,
00995 //                                Eigen::Vector2d &p, Eigen::Vector2d &t, int maxSteps, double accuracy, bool quiet)
00996 //{
00997 //  double hint;
00998 //  Eigen::Vector2d r;
00999 //  std::vector<double> elements = getElementVector (nurbs);
01000 //  double points[2];
01001 //
01002 //  if (phint == NULL)
01003 //  {
01004 //    double d_shortest (DBL_MAX);
01005 //    for (unsigned i = 0; i < elements.size () - 1; i++)
01006 //    {
01007 //      double d;
01008 //
01009 //      double xi = elements[i] + 0.5 * (elements[i + 1] - elements[i]);
01010 //
01011 //      nurbs.Evaluate (xi, 0, 2, points);
01012 //      p (0) = points[0];
01013 //      p (1) = points[1];
01014 //
01015 //      r = p - pt;
01016 //
01017 //      d = r.norm ();
01018 //
01019 //      if (d < d_shortest)
01020 //      {
01021 //        d_shortest = d;
01022 //        hint = xi;
01023 //      }
01024 //    }
01025 //  }
01026 //  else
01027 //  {
01028 //    hint = *phint;
01029 //  }
01030 //
01031 //  return inverseMapping (nurbs, pt, hint, error, p, t, maxSteps, accuracy, quiet);
01032 //}
01033 
01034 double
01035 FittingCurve2dAPDM::findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double hint)
01036 {
01037   // evaluate hint
01038   double param = hint;
01039   double points[2];
01040   nurbs.Evaluate (param, 0, 2, points);
01041   Eigen::Vector2d p (points[0], points[1]);
01042   Eigen::Vector2d r = p - pt;
01043 
01044   double d_shortest_hint = r.squaredNorm ();
01045   double d_shortest_elem (DBL_MAX);
01046 
01047   // evaluate elements
01048   std::vector<double> elements = pcl::on_nurbs::FittingCurve2dAPDM::getElementVector (nurbs);
01049   double seg = 1.0 / (nurbs.Order () - 1);
01050 
01051   for (unsigned i = 0; i < elements.size () - 1; i++)
01052   {
01053     double &xi0 = elements[i];
01054     double &xi1 = elements[i + 1];
01055     double dxi = xi1 - xi0;
01056 
01057     for (unsigned j = 0; j < nurbs.Order (); j++)
01058     {
01059       double xi = xi0 + (seg * j) * dxi;
01060 
01061       nurbs.Evaluate (xi, 0, 2, points);
01062       p (0) = points[0];
01063       p (1) = points[1];
01064 
01065       r = p - pt;
01066 
01067       double d = r.squaredNorm ();
01068 
01069       if (d < d_shortest_elem)
01070       {
01071         d_shortest_elem = d;
01072         param = xi;
01073       }
01074     }
01075   }
01076 
01077   if (d_shortest_hint < d_shortest_elem)
01078     return hint;
01079   else
01080     return param;
01081 }
01082 
01083 double
01084 FittingCurve2dAPDM::findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt)
01085 {
01086   double param (0.0);
01087   Eigen::Vector2d p, r;
01088   std::vector<double> elements = pcl::on_nurbs::FittingCurve2dAPDM::getElementVector (nurbs);
01089   double points[2];
01090 
01091   double d_shortest (DBL_MAX);
01092   double seg = 1.0 / (nurbs.Order () - 1);
01093 
01094   for (unsigned i = 0; i < elements.size () - 1; i++)
01095   {
01096     double &xi0 = elements[i];
01097     double &xi1 = elements[i + 1];
01098     double dxi = xi1 - xi0;
01099 
01100     for (unsigned j = 0; j < nurbs.Order (); j++)
01101     {
01102       double xi = xi0 + (seg * j) * dxi;
01103 
01104       nurbs.Evaluate (xi, 0, 2, points);
01105       p (0) = points[0];
01106       p (1) = points[1];
01107 
01108       r = p - pt;
01109 
01110       double d = r.squaredNorm ();
01111 
01112       if (d < d_shortest)
01113       {
01114         d_shortest = d;
01115         param = xi;
01116       }
01117     }
01118   }
01119 
01120   return param;
01121 }
01122 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:24:08