fitting_curve_2d_pdm.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_pdm.h>
00039 #include <stdexcept>
00040 
00041 using namespace pcl;
00042 using namespace on_nurbs;
00043 
00044 FittingCurve2dPDM::FittingCurve2dPDM (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 FittingCurve2dPDM::FittingCurve2dPDM (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 FittingCurve2dPDM::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 FittingCurve2dPDM::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 FittingCurve2dPDM::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 FittingCurve2dPDM::assemble (const Parameter &parameter)
00118 {
00119   int cp_red = m_nurbs.m_order - 2;
00120   int ncp = m_nurbs.m_cv_count - 2 * cp_red;
00121   int nCageReg = m_nurbs.m_cv_count - 2 * cp_red;
00122   int nInt = int (m_data->interior.size ());
00123 
00124   double wInt = 1.0;
00125   if (!m_data->interior_weight.empty ())
00126     wInt = m_data->interior_weight[0];
00127 
00128   unsigned nrows = nInt + nCageReg;
00129 
00130   m_solver.assign (nrows, ncp, 2);
00131 
00132   unsigned row (0);
00133 
00134   if (wInt > 0.0)
00135     assembleInterior (wInt, parameter.rScale, row);
00136 
00137   if (parameter.smoothness > 0.0)
00138     addCageRegularisation (parameter.smoothness, row);
00139 
00140   if (row < nrows)
00141   {
00142     m_solver.resize (row);
00143     if (!m_quiet)
00144       printf ("[FittingCurve2dPDM::assemble] Warning: rows do not match: %d %d\n", row, nrows);
00145   }
00146 }
00147 
00148 double
00149 FittingCurve2dPDM::solve (double damp)
00150 {
00151   double cps_diff (0.0);
00152 
00153   if (m_solver.solve ())
00154     cps_diff = updateCurve (damp);
00155 
00156   return cps_diff;
00157 }
00158 
00159 double
00160 FittingCurve2dPDM::updateCurve (double damp)
00161 {
00162   int cp_red = m_nurbs.m_order - 2;
00163   int ncp = m_nurbs.m_cv_count - 2 * cp_red;
00164 
00165   double cps_diff (0.0);
00166   double cps_diff_max (0.0);
00167 
00168   for (int j = 0; j < ncp; j++)
00169   {
00170 
00171     ON_3dPoint cp_prev;
00172     m_nurbs.GetCV (j, cp_prev);
00173 
00174     double x = m_solver.x (j, 0);
00175     double y = m_solver.x (j, 1);
00176 
00177     cps_diff += sqrt ((x - cp_prev.x) * (x - cp_prev.x) + (y - cp_prev.y) * (y - cp_prev.y));
00178 
00179     if (cps_diff > cps_diff_max)
00180       cps_diff_max = cps_diff;
00181 
00182     ON_3dPoint cp;
00183     cp.x = cp_prev.x + damp * (x - cp_prev.x);
00184     cp.y = cp_prev.y + damp * (y - cp_prev.y);
00185     cp.z = 0.0;
00186 
00187     m_nurbs.SetCV (j, cp);
00188 
00189   }
00190 
00191   for (int j = 0; j < 2 * cp_red; j++)
00192   {
00193     ON_3dPoint cp;
00194     m_nurbs.GetCV (2 * cp_red - 1 - j, cp);
00195     m_nurbs.SetCV (m_nurbs.m_cv_count - 1 - j, cp);
00196   }
00197 
00198   return cps_diff_max;
00199 }
00200 
00201 void
00202 FittingCurve2dPDM::addCPsOnClosestPointViolation (double max_error)
00203 {
00204   std::vector<double> elements = getElementVector (m_nurbs);
00205   //  m_data->interior_line_start.clear ();
00206   //  m_data->interior_line_end.clear ();
00207 
00208   int nknots (0);
00209 
00210   for (unsigned i = 0; i < elements.size () - 1; i++)
00211   {
00212 
00213     bool inserted (false);
00214     double dxi = elements[i + 1] - elements[i];
00215 
00216     {
00217       double xi = elements[i];
00218       double points[2];
00219       Eigen::Vector2d p1, p2;
00220       m_nurbs.Evaluate (xi, 0, 2, points);
00221       p1 (0) = points[0];
00222       p1 (1) = points[1];
00223 
00224       unsigned idx = NurbsTools::getClosestPoint (p1, m_data->interior);
00225       p2 = m_data->interior[idx];
00226 
00227       double d = (p2 - p1).squaredNorm ();
00228 
00229       if (d > (max_error * max_error))
00230       {
00231         m_nurbs.InsertKnot (xi + 0.5 * dxi, 1);
00232         //        m_data->interior_line_start.push_back (p2);
00233         //        m_data->interior_line_end.push_back (p1);
00234         nknots++;
00235         inserted = true;
00236       }
00237     }
00238 
00239     if (!inserted)
00240     {
00241       double xi = elements[i] + 0.5 * dxi;
00242       double points[2];
00243       Eigen::Vector2d p1, p2;
00244       m_nurbs.Evaluate (xi, 0, 2, points);
00245       p1 (0) = points[0];
00246       p1 (1) = points[1];
00247 
00248       unsigned idx = NurbsTools::getClosestPoint (p1, m_data->interior);
00249       p2 = m_data->interior[idx];
00250 
00251       double d = (p2 - p1).squaredNorm ();
00252 
00253       if (d > (max_error * max_error))
00254       {
00255         m_nurbs.InsertKnot (xi, 1);
00256         //        m_data->interior_line_start.push_back (p2);
00257         //        m_data->interior_line_end.push_back (p1);
00258         nknots++;
00259       }
00260     }
00261 
00262   }
00263   //  printf("[FittingCurve2dPDM::addCPsOnClosestPointViolation] %d knots inserted (%d, %d)\n", nknots,
00264   //      m_nurbs.CVCount(), m_nurbs.KnotCount());
00265 }
00266 
00267 ON_NurbsCurve
00268 FittingCurve2dPDM::removeCPsOnLine (const ON_NurbsCurve &nurbs, double min_curve_th)
00269 {
00270   int cp_red = nurbs.Order () - 2;
00271   int ncp = nurbs.CVCount () - 2 * cp_red;
00272 
00273   std::vector<ON_3dPoint> cps;
00274 
00275   for (int j = 1; j < ncp + 1; j++)
00276   {
00277     ON_3dPoint cp0, cp1, cp2;
00278     nurbs.GetCV ((j + 0) % ncp, cp0);
00279     nurbs.GetCV ((j - 1) % ncp, cp1);
00280     nurbs.GetCV ((j + 1) % ncp, cp2);
00281 
00282     Eigen::Vector3d v1 (cp1.x - cp0.x, cp1.y - cp0.y, cp1.z - cp0.z);
00283     Eigen::Vector3d v2 (cp2.x - cp0.x, cp2.y - cp0.y, cp2.z - cp0.z);
00284     v1.normalize ();
00285     v2.normalize ();
00286 
00287     double d = v1.dot (v2);
00288 
00289     if (d >= min_curve_th)
00290     {
00291       cps.push_back (cp0);
00292     }
00293 
00294   }
00295 
00296   int order = nurbs.Order ();
00297   ON_NurbsCurve nurbs_opt = ON_NurbsCurve (2, false, order, int (cps.size ()) + 2 * cp_red);
00298   nurbs_opt.MakePeriodicUniformKnotVector (1.0 / double (cps.size ()));
00299   nurbs_opt.m_knot[cp_red] = 0.0;
00300   nurbs_opt.m_knot[nurbs_opt.m_knot_capacity - cp_red - 1] = 1.0;
00301 
00302   for (unsigned j = 0; j < cps.size (); j++)
00303     nurbs_opt.SetCV (j + cp_red, cps[j]);
00304 
00305   for (int j = 0; j < cp_red; j++)
00306   {
00307     ON_3dPoint cp;
00308     nurbs_opt.GetCV (nurbs_opt.m_cv_count - 1 - cp_red + j, cp);
00309     nurbs_opt.SetCV (j, cp);
00310 
00311     nurbs_opt.GetCV (cp_red - j, cp);
00312     nurbs_opt.SetCV (nurbs_opt.m_cv_count - 1 - j, cp);
00313   }
00314 
00315   return nurbs_opt;
00316 }
00317 
00318 void
00319 FittingCurve2dPDM::addPointConstraint (const double &param, const Eigen::Vector2d &point, double weight, unsigned &row)
00320 {
00321   int cp_red = m_nurbs.m_order - 2;
00322   int ncp = m_nurbs.m_cv_count - 2 * cp_red;
00323   double *N = new double[m_nurbs.m_order * m_nurbs.m_order];
00324 
00325   int E = ON_NurbsSpanIndex (m_nurbs.m_order, m_nurbs.m_cv_count, m_nurbs.m_knot, param, 0, 0);
00326 
00327   ON_EvaluateNurbsBasis (m_nurbs.m_order, m_nurbs.m_knot + E, param, N);
00328 
00329   m_solver.f (row, 0, point (0) * weight);
00330   m_solver.f (row, 1, point (1) * weight);
00331 
00332   for (int i = 0; i < m_nurbs.m_order; i++)
00333     m_solver.K (row, (E + i) % ncp, weight * N[i]);
00334 
00335   row++;
00336 
00337   delete [] N;
00338 }
00339 
00340 void
00341 FittingCurve2dPDM::addCageRegularisation (double weight, unsigned &row)
00342 {
00343   int cp_red = (m_nurbs.m_order - 2);
00344   int ncp = (m_nurbs.m_cv_count - 2 * cp_red);
00345 
00346   //  m_data->interior_line_start.clear();
00347   //  m_data->interior_line_end.clear();
00348   for (int j = 1; j < ncp + 1; j++)
00349   {
00350 
00351     m_solver.f (row, 0, 0.0);
00352     m_solver.f (row, 1, 0.0);
00353 
00354     m_solver.K (row, (j + 0) % ncp, -2.0 * weight);
00355     m_solver.K (row, (j - 1) % ncp, 1.0 * weight);
00356     m_solver.K (row, (j + 1) % ncp, 1.0 * weight);
00357 
00358     row++;
00359   }
00360 }
00361 
00362 ON_NurbsCurve
00363 FittingCurve2dPDM::initCPsNurbsCurve2D (int order, const vector_vec2d &cps)
00364 {
00365   int cp_red = order - 2;
00366   ON_NurbsCurve nurbs;
00367   if (cps.size () < 3 || cps.size () < (2 * cp_red + 1))
00368   {
00369     printf ("[FittingCurve2dPDM::initCPsNurbsCurve2D] Warning, number of control points too low.\n");
00370     return nurbs;
00371   }
00372 
00373   int ncps = int (cps.size ()) + 2 * cp_red; // +2*cp_red for smoothness and +1 for closing
00374   nurbs = ON_NurbsCurve (2, false, order, ncps);
00375   nurbs.MakePeriodicUniformKnotVector (1.0 / (ncps - order + 1));
00376 
00377   for (int j = 0; j < cps.size (); j++)
00378     nurbs.SetCV (cp_red + j, ON_3dPoint (cps[j] (0), cps[j] (1), 0.0));
00379 
00380   // close nurbs
00381   nurbs.SetCV (cp_red + int (cps.size ()), ON_3dPoint (cps[0] (0), cps[0] (1), 0.0));
00382 
00383   // make smooth at closing point
00384   for (int j = 0; j < cp_red; j++)
00385   {
00386     ON_3dPoint cp;
00387     nurbs.GetCV (nurbs.CVCount () - 1 - cp_red + j, cp);
00388     nurbs.SetCV (j, cp);
00389 
00390     nurbs.GetCV (cp_red - j, cp);
00391     nurbs.SetCV (nurbs.CVCount () - 1 - j, cp);
00392   }
00393 
00394   return nurbs;
00395 }
00396 
00397 ON_NurbsCurve
00398 FittingCurve2dPDM::initNurbsCurve2D (int order, const vector_vec2d &data, int ncps, double radiusF)
00399 {
00400   if (data.empty ())
00401     printf ("[FittingCurve2dPDM::initNurbsCurve2D] Warning, no boundary parameters available\n");
00402 
00403   Eigen::Vector2d mean = NurbsTools::computeMean (data);
00404 
00405   unsigned s = unsigned (data.size ());
00406 
00407   double r (0.0);
00408   for (unsigned i = 0; i < s; i++)
00409   {
00410     Eigen::Vector2d d = data[i] - mean;
00411     double sn = d.squaredNorm ();
00412     if (sn > r)
00413       r = sn;
00414   }
00415   r = radiusF * sqrt (r);
00416 
00417   if (ncps < 2 * order)
00418     ncps = 2 * order;
00419 
00420   ON_NurbsCurve nurbs = ON_NurbsCurve (2, false, order, ncps);
00421   nurbs.MakePeriodicUniformKnotVector (1.0 / (ncps - order + 1));
00422 
00423   double dcv = (2.0 * M_PI) / (ncps - order + 1);
00424   Eigen::Vector2d cv;
00425   for (int j = 0; j < ncps; j++)
00426   {
00427     cv (0) = r * sin (dcv * j);
00428     cv (1) = r * cos (dcv * j);
00429     cv = cv + mean;
00430     nurbs.SetCV (j, ON_3dPoint (cv (0), cv (1), 0.0));
00431   }
00432 
00433   return nurbs;
00434 }
00435 
00436 void
00437 FittingCurve2dPDM::reverse (ON_NurbsCurve &curve)
00438 {
00439 
00440   ON_NurbsCurve curve2 = curve;
00441   for (int i = 0; i < curve.CVCount (); i++)
00442   {
00443     int j = curve.CVCount () - 1 - i;
00444     ON_3dPoint p;
00445     curve.GetCV (i, p);
00446     curve2.SetCV (j, p);
00447   }
00448   curve = curve2;
00449 }
00450 
00451 //ON_NurbsCurve FittingCurve2dPDM::initNurbsCurvePCA(int order, const vector_vec2d &data)
00452 //{
00453 //  if (data.empty())
00454 //    printf("[FittingCurve2dPDM::initNurbsCurvePCA] Warning, no boundary parameters available\n");
00455 //
00456 //  Eigen::Vector3d mean;
00457 //  Eigen::Matrix3d eigenvectors;
00458 //  Eigen::Vector3d eigenvalues;
00459 //
00460 //  unsigned s = data.size();
00461 //
00462 //  NurbsTools::pca(data, mean, eigenvectors, eigenvalues);
00463 //
00464 //  eigenvalues = eigenvalues / s; // seems that the eigenvalues are dependent on the number of points (???)
00465 //
00466 //  double r = 2.0 * sqrt(eigenvalues(0));
00467 //
00468 //  int ncpsV(2 * order);
00469 //  ON_NurbsCurve nurbs = ON_NurbsCurve(3, false, order, ncpsV);
00470 //  nurbs.MakePeriodicUniformKnotVector(1.0 / (ncpsV - order + 1));
00471 //
00472 //  double dcv = (2.0 * M_PI) / (ncpsV - order + 1);
00473 //  Eigen::Vector3d cv, cv_t;
00474 //  for (int j = 0; j < ncpsV; j++) {
00475 //    cv(0) = r * sin(dcv * j);
00476 //    cv(1) = r * cos(dcv * j);
00477 //    cv(2) = 0.0;
00478 //    cv_t = eigenvectors * cv + mean;
00479 //    nurbs.SetCV(j, ON_3dPoint(cv_t(0), cv_t(1), cv_t(2)));
00480 //  }
00481 //
00482 //  return nurbs;
00483 //}
00484 
00485 std::vector<double>
00486 FittingCurve2dPDM::getElementVector (const ON_NurbsCurve &nurbs)
00487 {
00488   std::vector<double> result;
00489 
00490   int idx_min = 0;
00491   int idx_max = nurbs.m_knot_capacity - 1;
00492   if (nurbs.IsClosed ())
00493   {
00494     idx_min = nurbs.m_order - 2;
00495     idx_max = nurbs.m_knot_capacity - nurbs.m_order + 1;
00496   }
00497 
00498   const double* knotsU = nurbs.Knot ();
00499 
00500   result.push_back (knotsU[idx_min]);
00501 
00502   //for(int E=(m_nurbs.m_order[0]-2); E<(m_nurbs.m_knot_capacity[0]-m_nurbs.m_order[0]+2); E++) {
00503   for (int E = idx_min + 1; E <= idx_max; E++)
00504   {
00505 
00506     if (knotsU[E] != knotsU[E - 1]) // do not count double knots
00507       result.push_back (knotsU[E]);
00508 
00509   }
00510 
00511   return result;
00512 }
00513 
00514 void
00515 FittingCurve2dPDM::assembleInterior (double wInt, double rScale, unsigned &row)
00516 {
00517   int nInt = int (m_data->interior.size ());
00518   m_data->interior_error.clear ();
00519   m_data->interior_normals.clear ();
00520   m_data->interior_line_start.clear ();
00521   m_data->interior_line_end.clear ();
00522 
00523   for (int p = 0; p < nInt; p++)
00524   {
00525     Eigen::Vector2d &pcp = m_data->interior[p];
00526 
00527     // inverse mapping
00528     double param;
00529     Eigen::Vector2d pt, t;
00530     double error;
00531     if (p < int (m_data->interior_param.size ()))
00532     {
00533       param = findClosestElementMidPoint (m_nurbs, pcp, m_data->interior_param[p]);
00534       param = inverseMapping (m_nurbs, pcp, param, error, pt, t, rScale, in_max_steps, in_accuracy, m_quiet);
00535       m_data->interior_param[p] = param;
00536     }
00537     else
00538     {
00539       param = findClosestElementMidPoint (m_nurbs, pcp);
00540       param = inverseMapping (m_nurbs, pcp, param, error, pt, t, rScale, in_max_steps, in_accuracy, m_quiet);
00541       m_data->interior_param.push_back (param);
00542     }
00543 
00544     m_data->interior_error.push_back (error);
00545 
00546     if (p < int (m_data->interior_weight.size ()))
00547       wInt = m_data->interior_weight[p];
00548 
00549     m_data->interior_line_start.push_back (pcp);
00550     m_data->interior_line_end.push_back (pt);
00551 
00552     addPointConstraint (m_data->interior_param[p], m_data->interior[p], wInt, row);
00553   }
00554 }
00555 
00556 double
00557 FittingCurve2dPDM::inverseMapping (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, const double &hint,
00558                                    double &error, Eigen::Vector2d &p, Eigen::Vector2d &t, double rScale, int maxSteps,
00559                                    double accuracy, bool quiet)
00560 {
00561   if (nurbs.Order () == 2)
00562     return inverseMappingO2 (nurbs, pt, error, p, t);
00563 
00564   //int cp_red = (nurbs.m_order - 2);
00565   //int ncpj = int (nurbs.m_cv_count - 2 * cp_red);
00566   double pointAndTangents[4];
00567 
00568   double current, delta;
00569   Eigen::Vector2d r;
00570   std::vector<double> elements = getElementVector (nurbs);
00571   double minU = elements[0];
00572   double maxU = elements[elements.size () - 1];
00573 
00574   current = hint;
00575 
00576   for (int k = 0; k < maxSteps; k++)
00577   {
00578 
00579     nurbs.Evaluate (current, 1, 2, pointAndTangents);
00580 
00581     p (0) = pointAndTangents[0];
00582     p (1) = pointAndTangents[1];
00583 
00584     t (0) = pointAndTangents[2];
00585     t (1) = pointAndTangents[3];
00586 
00587     r = p - pt;
00588 
00589     // step width control
00590     int E = findElement (current, elements);
00591     double e = elements[E + 1] - elements[E];
00592 
00593     delta = -(0.5 * e * rScale) * r.dot (t) / t.norm (); //  A.ldlt().solve(b);
00594 
00595     //    e = 0.5 * std::abs<double> (e);
00596     //    if (delta > e)
00597     //      delta = e;
00598     //    if (delta < -e)
00599     //      delta = -e;
00600 
00601     if (std::abs (delta) < accuracy)
00602     {
00603 
00604       error = r.norm ();
00605       return current;
00606 
00607     }
00608     else
00609     {
00610       current = current + delta;
00611 
00612       if (current < minU)
00613         current = maxU - (minU - current);
00614       else if (current > maxU)
00615         current = minU + (current - maxU);
00616 
00617     }
00618 
00619   }
00620 
00621   error = r.norm ();
00622 
00623   if (!quiet)
00624   {
00625     printf ("[FittingCurve2dPDM::inverseMapping] Warning: Method did not converge (%e %d).\n", accuracy, maxSteps);
00626     printf ("[FittingCurve2dPDM::inverseMapping] hint: %f current: %f delta: %f error: %f\n", hint, current, delta,
00627             error);
00628   }
00629 
00630   return current;
00631 }
00632 
00633 double
00634 FittingCurve2dPDM::inverseMappingO2 (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double &error,
00635                                      Eigen::Vector2d &p, Eigen::Vector2d &t)
00636 {
00637   if (nurbs.Order () != 2)
00638     printf ("[FittingCurve2dPDM::inverseMappingO2] Error, order not 2 (polynomial degree 1)\n");
00639 
00640   std::vector<double> elements = getElementVector (nurbs);
00641 
00642   Eigen::Vector2d min_pt;
00643   double min_param (DBL_MAX);
00644   double min_dist (DBL_MAX);
00645   error = DBL_MAX;
00646   int is_corner (-1);
00647 
00648   for (unsigned i = 0; i < elements.size () - 1; i++)
00649   {
00650     Eigen::Vector2d p1;
00651     nurbs.Evaluate (elements[i], 0, 2, &p1 (0));
00652 
00653     Eigen::Vector2d p2;
00654     nurbs.Evaluate (elements[i + 1], 0, 2, &p2 (0));
00655 
00656     Eigen::Vector2d d1 (p2 (0) - p1 (0), p2 (1) - p1 (1));
00657     Eigen::Vector2d d2 (pt (0) - p1 (0), pt (1) - p1 (1));
00658 
00659     double d1_norm = d1.norm ();
00660 
00661     double d0_norm = d1.dot (d2) / d1_norm;
00662     Eigen::Vector2d d0 = d1 * d0_norm / d1_norm;
00663     Eigen::Vector2d p0 = p1 + d0;
00664 
00665     if (d0_norm < 0.0)
00666     {
00667       double tmp_dist = (p1 - pt).norm ();
00668       if (tmp_dist < min_dist)
00669       {
00670         min_dist = tmp_dist;
00671         min_pt = p1;
00672         min_param = elements[i];
00673         is_corner = i;
00674       }
00675     }
00676     else if (d0_norm >= d1_norm)
00677     {
00678       double tmp_dist = (p2 - pt).norm ();
00679       if (tmp_dist < min_dist)
00680       {
00681         min_dist = tmp_dist;
00682         min_pt = p2;
00683         min_param = elements[i + 1];
00684         is_corner = i + 1;
00685       }
00686     }
00687     else
00688     { // p0 lies on line segment
00689       double tmp_dist = (p0 - pt).norm ();
00690       if (tmp_dist < min_dist)
00691       {
00692         min_dist = tmp_dist;
00693         min_pt = p0;
00694         min_param = elements[i] + (d0_norm / d1_norm) * (elements[i + 1] - elements[i]);
00695         is_corner = -1;
00696       }
00697     }
00698   }
00699 
00700   if (is_corner >= 0)
00701   {
00702     double param1, param2;
00703     if (is_corner == 0 || is_corner == elements.size () - 1)
00704     {
00705       double x0a = elements[0];
00706       double x0b = elements[elements.size () - 1];
00707       double xa = elements[1];
00708       double xb = elements[elements.size () - 2];
00709 
00710       param1 = x0a + 0.5 * (xa - x0a);
00711       param2 = x0b + 0.5 * (xb - x0b);
00712     }
00713     else
00714     {
00715       double x0 = elements[is_corner];
00716       double x1 = elements[is_corner - 1];
00717       double x2 = elements[is_corner + 1];
00718 
00719       param1 = x0 + 0.5 * (x1 - x0);
00720       param2 = x0 + 0.5 * (x2 - x0);
00721     }
00722 
00723     double pt1[4];
00724     nurbs.Evaluate (param1, 1, 2, pt1);
00725     Eigen::Vector2d t1 (pt1[2], pt1[3]);
00726     t1.normalize ();
00727 
00728     double pt2[4];
00729     nurbs.Evaluate (param2, 1, 2, pt2);
00730     Eigen::Vector2d t2 (pt2[2], pt2[3]);
00731     t2.normalize ();
00732 
00733     t = 0.5 * (t1 + t2);
00734   }
00735   else
00736   {
00737     double point_tangent[4];
00738     nurbs.Evaluate (min_param, 1, 2, point_tangent);
00739     t (0) = point_tangent[2];
00740     t (1) = point_tangent[3];
00741   }
00742 
00743   t.normalize ();
00744   p = min_pt;
00745   return min_param;
00746 }
00747 
00748 //double
00749 //FittingCurve2dPDM::inverseMapping (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double* phint, double &error,
00750 //                                Eigen::Vector2d &p, Eigen::Vector2d &t, int maxSteps, double accuracy, bool quiet)
00751 //{
00752 //  double hint;
00753 //  Eigen::Vector2d r;
00754 //  std::vector<double> elements = getElementVector (nurbs);
00755 //  double points[2];
00756 //
00757 //  if (phint == NULL)
00758 //  {
00759 //    double d_shortest (DBL_MAX);
00760 //    for (unsigned i = 0; i < elements.size () - 1; i++)
00761 //    {
00762 //      double d;
00763 //
00764 //      double xi = elements[i] + 0.5 * (elements[i + 1] - elements[i]);
00765 //
00766 //      nurbs.Evaluate (xi, 0, 2, points);
00767 //      p (0) = points[0];
00768 //      p (1) = points[1];
00769 //
00770 //      r = p - pt;
00771 //
00772 //      d = r.norm ();
00773 //
00774 //      if (d < d_shortest)
00775 //      {
00776 //        d_shortest = d;
00777 //        hint = xi;
00778 //      }
00779 //    }
00780 //  }
00781 //  else
00782 //  {
00783 //    hint = *phint;
00784 //  }
00785 //
00786 //  return inverseMapping (nurbs, pt, hint, error, p, t, maxSteps, accuracy, quiet);
00787 //}
00788 
00789 double
00790 FittingCurve2dPDM::findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double hint)
00791 {
00792   // evaluate hint
00793   double param = hint;
00794   double points[2];
00795   nurbs.Evaluate (param, 0, 2, points);
00796   Eigen::Vector2d p (points[0], points[1]);
00797   Eigen::Vector2d r = p - pt;
00798 
00799   double d_shortest_hint = r.squaredNorm ();
00800   double d_shortest_elem (DBL_MAX);
00801 
00802   // evaluate elements
00803   std::vector<double> elements = pcl::on_nurbs::FittingCurve2dPDM::getElementVector (nurbs);
00804   double seg = 1.0 / (nurbs.Order () - 1);
00805 
00806   for (unsigned i = 0; i < elements.size () - 1; i++)
00807   {
00808     double &xi0 = elements[i];
00809     double &xi1 = elements[i + 1];
00810     double dxi = xi1 - xi0;
00811 
00812     for (unsigned j = 0; j < nurbs.Order (); j++)
00813     {
00814       double xi = xi0 + (seg * j) * dxi;
00815 
00816       nurbs.Evaluate (xi, 0, 2, points);
00817       p (0) = points[0];
00818       p (1) = points[1];
00819 
00820       r = p - pt;
00821 
00822       double d = r.squaredNorm ();
00823 
00824       if (d < d_shortest_elem)
00825       {
00826         d_shortest_elem = d;
00827         param = xi;
00828       }
00829     }
00830   }
00831 
00832   if (d_shortest_hint < d_shortest_elem)
00833     return hint;
00834   else
00835     return param;
00836 }
00837 
00838 double
00839 FittingCurve2dPDM::findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt)
00840 {
00841   double param (0.0);
00842   Eigen::Vector2d p, r;
00843   std::vector<double> elements = pcl::on_nurbs::FittingCurve2dPDM::getElementVector (nurbs);
00844   double points[2];
00845 
00846   double d_shortest (DBL_MAX);
00847   double seg = 1.0 / (nurbs.Order () - 1);
00848 
00849   for (unsigned i = 0; i < elements.size () - 1; i++)
00850   {
00851     double &xi0 = elements[i];
00852     double &xi1 = elements[i + 1];
00853     double dxi = xi1 - xi0;
00854 
00855     for (unsigned j = 0; j < nurbs.Order (); j++)
00856     {
00857       double xi = xi0 + (seg * j) * dxi;
00858 
00859       nurbs.Evaluate (xi, 0, 2, points);
00860       p (0) = points[0];
00861       p (1) = points[1];
00862 
00863       r = p - pt;
00864 
00865       double d = r.squaredNorm ();
00866 
00867       if (d < d_shortest)
00868       {
00869         d_shortest = d;
00870         param = xi;
00871       }
00872     }
00873   }
00874 
00875   return param;
00876 }
00877 


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