fitting_cylinder_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 <stdexcept>
00039 #include <pcl/surface/on_nurbs/fitting_cylinder_pdm.h>
00040 
00041 using namespace pcl;
00042 using namespace on_nurbs;
00043 using namespace Eigen;
00044 
00045 FittingCylinder::FittingCylinder (int order, NurbsDataSurface *data)
00046 {
00047   if (order < 2)
00048     throw std::runtime_error ("[FittingCylinder::FittingCylinder] Error order to low (order<2).");
00049 
00050   ON::Begin ();
00051 
00052   m_data = data;
00053   m_nurbs = initNurbsPCACylinder (order, m_data);
00054 
00055   this->init ();
00056 }
00057 
00058 FittingCylinder::FittingCylinder (NurbsDataSurface *data, const ON_NurbsSurface &ns)
00059 {
00060   ON::Begin ();
00061 
00062   m_nurbs = ON_NurbsSurface (ns);
00063   m_data = data;
00064 
00065   this->init ();
00066 }
00067 
00068 void
00069 FittingCylinder::init ()
00070 {
00071   in_max_steps = 100;
00072   in_accuracy = 1e-4;
00073 
00074   m_quiet = true;
00075 }
00076 
00077 void
00078 FittingCylinder::refine (int dim)
00079 {
00080   std::vector<double> xi;
00081   std::vector<double> elements = getElementVector (m_nurbs, dim);
00082 
00083   for (unsigned i = 0; i < elements.size () - 1; i++)
00084     xi.push_back (elements[i] + 0.5 * (elements[i + 1] - elements[i]));
00085 
00086   for (unsigned i = 0; i < xi.size (); i++)
00087     m_nurbs.InsertKnot (dim, xi[i], 1);
00088 }
00089 
00090 void
00091 FittingCylinder::refine (int dim, double param)
00092 {
00093   std::vector<double> elements = getElementVector (m_nurbs, dim);
00094 
00095   if (param == elements[elements.size () - 1])
00096   {
00097     int i = int (elements.size ()) - 2;
00098     double xi = elements[i] + 0.5 * (elements[i + 1] - elements[i]);
00099     m_nurbs.InsertKnot (dim, xi);
00100     return;
00101   }
00102 
00103   for (unsigned i = 0; i < elements.size () - 1; i++)
00104   {
00105     if (param >= elements[i] && param < elements[i + 1])
00106     {
00107       double xi = elements[i] + 0.5 * (elements[i + 1] - elements[i]);
00108       m_nurbs.InsertKnot (dim, xi);
00109     }
00110   }
00111 }
00112 
00113 void
00114 FittingCylinder::refine (int dim, unsigned span_index)
00115 {
00116   std::vector<double> elements = getElementVector (m_nurbs, dim);
00117 
00118   if (span_index > int (elements.size ()) - 2)
00119   {
00120     printf ("[NurbsTools::refine(int, unsigned)] Warning span index out of bounds\n");
00121     return;
00122   }
00123 
00124   double xi = elements[span_index] + 0.5 * (elements[span_index + 1] - elements[span_index]);
00125 
00126   m_nurbs.InsertKnot (dim, xi);
00127 }
00128 
00129 void
00130 FittingCylinder::assemble (double smoothness)
00131 {
00132   int cp_red = (m_nurbs.m_order[1] - 2);
00133   int ncp = m_nurbs.m_cv_count[0] * (m_nurbs.m_cv_count[1] - 2 * cp_red);
00134   int nInt = int (m_data->interior.size ());
00135   int nCageRegInt = (m_nurbs.m_cv_count[0] - 2) * (m_nurbs.m_cv_count[1] - 2 * cp_red);
00136   int nCageRegBnd = 2 * (m_nurbs.m_cv_count[1] - 2 * cp_red);
00137 
00138   double wInt = 1.0;
00139   double wCageRegInt = smoothness;
00140   double wCageRegBnd = smoothness;
00141 
00142   int nrows = nInt + nCageRegInt + nCageRegBnd;
00143 
00144   if (!m_quiet)
00145     printf ("[FittingCylinder::assemble] %dx%d (invmap: %f %d)\n", nrows, ncp, in_accuracy, in_max_steps);
00146 
00147   m_solver.assign (nrows, ncp, 3);
00148 
00149   unsigned row (0);
00150 
00151   // interior points should lie on surface
00152   assembleInterior (wInt, row);
00153 
00154   // cage regularisation
00155   if (nCageRegInt > 0)
00156     addCageInteriorRegularisation (wCageRegInt, row);
00157 
00158   if (nCageRegBnd > 0)
00159   {
00160     addCageBoundaryRegularisation (wCageRegBnd, WEST, row);
00161     addCageBoundaryRegularisation (wCageRegBnd, EAST, row);
00162   }
00163 }
00164 
00165 void
00166 FittingCylinder::solve (double damp)
00167 {
00168   if (m_solver.solve ())
00169     updateSurf (damp);
00170 }
00171 
00172 void
00173 FittingCylinder::updateSurf (double)
00174 {
00175   int cp_red = (m_nurbs.m_order[1] - 2);
00176 
00177   for (int j = 0; j < m_nurbs.m_cv_count[1] - 2 * cp_red; j++)
00178   {
00179     for (int i = 0; i < m_nurbs.m_cv_count[0]; i++)
00180     {
00181 
00182       int A = grc2gl (i, j);
00183 
00184       ON_3dPoint cp;
00185       cp.x = m_solver.x (A, 0);
00186       cp.y = m_solver.x (A, 1);
00187       cp.z = m_solver.x (A, 2);
00188 
00189       m_nurbs.SetCV (i, j + cp_red, cp);
00190     }
00191   }
00192 
00193   for (int j = 0; j < cp_red; j++)
00194   {
00195     for (int i = 0; i < m_nurbs.m_cv_count[0]; i++)
00196     {
00197 
00198       ON_3dPoint cp;
00199       m_nurbs.GetCV (i, m_nurbs.m_cv_count[1] - 1 - cp_red + j, cp);
00200       m_nurbs.SetCV (i, j, cp);
00201 
00202       m_nurbs.GetCV (i, cp_red - j, cp);
00203       m_nurbs.SetCV (i, m_nurbs.m_cv_count[1] - 1 - j, cp);
00204     }
00205   }
00206 }
00207 
00208 void
00209 FittingCylinder::setInvMapParams (int in_max_steps, double in_accuracy)
00210 {
00211   this->in_max_steps = in_max_steps;
00212   this->in_accuracy = in_accuracy;
00213 }
00214 
00215 ON_NurbsSurface
00216 FittingCylinder::initNurbsPCACylinder (int order, NurbsDataSurface *data)
00217 {
00218   Eigen::Vector3d mean;
00219   Eigen::Matrix3d eigenvectors;
00220   Eigen::Vector3d eigenvalues;
00221 
00222   unsigned s = unsigned (data->interior.size ());
00223 
00224   NurbsTools::pca (data->interior, mean, eigenvectors, eigenvalues);
00225 
00226   data->mean = mean;
00227   data->eigenvectors = eigenvectors;
00228 
00229   eigenvalues = eigenvalues / s; // seems that the eigenvalues are dependent on the number of points (???)
00230 
00231   Eigen::Vector3d v_max (0.0, 0.0, 0.0);
00232   Eigen::Vector3d v_min (DBL_MAX, DBL_MAX, DBL_MAX);
00233   for (unsigned i = 0; i < s; i++)
00234   {
00235     Eigen::Vector3d p (eigenvectors.inverse () * (data->interior[i] - mean));
00236 
00237     if (p (0) > v_max (0))
00238       v_max (0) = p (0);
00239     if (p (1) > v_max (1))
00240       v_max (1) = p (1);
00241     if (p (2) > v_max (2))
00242       v_max (2) = p (2);
00243 
00244     if (p (0) < v_min (0))
00245       v_min (0) = p (0);
00246     if (p (1) < v_min (1))
00247       v_min (1) = p (1);
00248     if (p (2) < v_min (2))
00249       v_min (2) = p (2);
00250   }
00251 
00252   int ncpsU (order);
00253   int ncpsV (2 * order + 4);
00254   ON_NurbsSurface nurbs (3, false, order, order, ncpsU, ncpsV);
00255   nurbs.MakeClampedUniformKnotVector (0, 1.0);
00256   nurbs.MakePeriodicUniformKnotVector (1, 1.0 / (ncpsV - order + 1));
00257 
00258   double dcu = (v_max (0) - v_min (0)) / (ncpsU - 1);
00259   double dcv = (2.0 * M_PI) / (ncpsV - order + 1);
00260 
00261   double ry = std::max<double> (std::fabs (v_min (1)), std::fabs (v_max (1)));
00262   double rz = std::max<double> (std::fabs (v_min (2)), std::fabs (v_max (2)));
00263 
00264   Eigen::Vector3d cv_t, cv;
00265   for (int i = 0; i < ncpsU; i++)
00266   {
00267     for (int j = 0; j < ncpsV; j++)
00268     {
00269       cv (0) = v_min (0) + dcu * i;
00270       cv (1) = ry * sin (dcv * j);
00271       cv (2) = rz * cos (dcv * j);
00272       cv_t = eigenvectors * cv + mean;
00273       nurbs.SetCV (i, j, ON_3dPoint (cv_t (0), cv_t (1), cv_t (2)));
00274     }
00275   }
00276 
00277   return nurbs;
00278 }
00279 
00280 std::vector<double>
00281 FittingCylinder::getElementVector (const ON_NurbsSurface &nurbs, int dim) // !
00282 {
00283   std::vector<double> result;
00284 
00285   if (dim == 0)
00286   {
00287     int idx_min = 0;
00288     int idx_max = nurbs.KnotCount (0) - 1;
00289     if (nurbs.IsClosed (0))
00290     {
00291       idx_min = nurbs.Order (0) - 2;
00292       idx_max = nurbs.KnotCount (0) - nurbs.Order (0) + 1;
00293     }
00294 
00295     const double* knotsU = nurbs.Knot (0);
00296 
00297     result.push_back (knotsU[idx_min]);
00298 
00299     //for(int E=(m_nurbs.m_order[0]-2); E<(m_nurbs.m_knot_capacity[0]-m_nurbs.m_order[0]+2); E++) {
00300     for (int E = idx_min + 1; E <= idx_max; E++)
00301     {
00302 
00303       if (knotsU[E] != knotsU[E - 1]) // do not count double knots
00304         result.push_back (knotsU[E]);
00305 
00306     }
00307 
00308   }
00309   else if (dim == 1)
00310   {
00311     int idx_min = 0;
00312     int idx_max = nurbs.KnotCount (1) - 1;
00313     if (nurbs.IsClosed (1))
00314     {
00315       idx_min = nurbs.Order (1) - 2;
00316       idx_max = nurbs.KnotCount (1) - nurbs.Order (1) + 1;
00317     }
00318     const double* knotsV = nurbs.Knot (1);
00319 
00320     result.push_back (knotsV[idx_min]);
00321 
00322     //for(int F=(m_nurbs.m_order[1]-2); F<(m_nurbs.m_knot_capacity[1]-m_nurbs.m_order[1]+2); F++) {
00323     for (int F = idx_min + 1; F <= idx_max; F++)
00324     {
00325 
00326       if (knotsV[F] != knotsV[F - 1])
00327         result.push_back (knotsV[F]);
00328 
00329     }
00330 
00331   }
00332   else
00333     printf ("[FittingCylinder::getElementVector] Error, index exceeds problem dimensions!\n");
00334 
00335   return result;
00336 }
00337 
00338 void
00339 FittingCylinder::assembleInterior (double wInt, unsigned &row)
00340 {
00341   m_data->interior_line_start.clear ();
00342   m_data->interior_line_end.clear ();
00343   m_data->interior_error.clear ();
00344   m_data->interior_normals.clear ();
00345   unsigned nInt = unsigned (m_data->interior.size ());
00346   for (unsigned p = 0; p < nInt; p++)
00347   {
00348     Vector3d pcp;
00349     pcp = m_data->interior[p];
00350 
00351     // inverse mapping
00352     Vector2d params;
00353     Vector3d pt, tu, tv, n;
00354     double error;
00355     if (p < m_data->interior_param.size ())
00356     {
00357       params = inverseMapping (m_nurbs, pcp, m_data->interior_param[p], error, pt, tu, tv, in_max_steps, in_accuracy);
00358       m_data->interior_param[p] = params;
00359     }
00360     else
00361     {
00362       params = findClosestElementMidPoint (m_nurbs, pcp);
00363       params = inverseMapping (m_nurbs, pcp, params, error, pt, tu, tv, in_max_steps, in_accuracy);
00364       m_data->interior_param.push_back (params);
00365     }
00366     m_data->interior_error.push_back (error);
00367 
00368     n = tu.cross (tv);
00369     n.normalize ();
00370 
00371     m_data->interior_normals.push_back (n);
00372     m_data->interior_line_start.push_back (pcp);
00373     m_data->interior_line_end.push_back (pt);
00374 
00375     addPointConstraint (params, pcp, wInt, row);
00376   }
00377 }
00378 
00379 void
00380 FittingCylinder::addPointConstraint (const Eigen::Vector2d &params, const Eigen::Vector3d &point, double weight,
00381                                      unsigned &row)
00382 {
00383   double *N0 = new double[m_nurbs.m_order[0] * m_nurbs.m_order[0]];
00384   double *N1 = new double[m_nurbs.m_order[1] * m_nurbs.m_order[1]];
00385 
00386   int E = ON_NurbsSpanIndex (m_nurbs.m_order[0], m_nurbs.m_cv_count[0], m_nurbs.m_knot[0], params (0), 0, 0);
00387   int F = ON_NurbsSpanIndex (m_nurbs.m_order[1], m_nurbs.m_cv_count[1], m_nurbs.m_knot[1], params (1), 0, 0);
00388 
00389   ON_EvaluateNurbsBasis (m_nurbs.m_order[0], m_nurbs.m_knot[0] + E, params (0), N0);
00390   ON_EvaluateNurbsBasis (m_nurbs.m_order[1], m_nurbs.m_knot[1] + F, params (1), N1);
00391 
00392   m_solver.f (row, 0, point (0) * weight);
00393   m_solver.f (row, 1, point (1) * weight);
00394   m_solver.f (row, 2, point (2) * weight);
00395 
00396   for (int i = 0; i < m_nurbs.m_order[0]; i++)
00397   {
00398 
00399     for (int j = 0; j < m_nurbs.m_order[1]; j++)
00400     {
00401 
00402       m_solver.K (row, lrc2gl (E, F, i, j), weight * N0[i] * N1[j]);
00403 
00404     } // j
00405 
00406   } // i
00407 
00408   row++;
00409 
00410   delete [] N1;
00411   delete [] N0;
00412 }
00413 
00414 void
00415 FittingCylinder::addCageInteriorRegularisation (double weight, unsigned &row)
00416 {
00417   int cp_red = (m_nurbs.m_order[1] - 2);
00418 
00419   for (int i = 1; i < (m_nurbs.m_cv_count[0] - 1); i++)
00420   {
00421     for (int j = 0; j < (m_nurbs.m_cv_count[1] - 2 * cp_red); j++)
00422     {
00423 
00424       m_solver.f (row, 0, 0.0);
00425       m_solver.f (row, 1, 0.0);
00426       m_solver.f (row, 2, 0.0);
00427 
00428       m_solver.K (row, grc2gl (i + 0, j + 0), -4.0 * weight);
00429       m_solver.K (row, grc2gl (i + 0, j - 1), 1.0 * weight);
00430       m_solver.K (row, grc2gl (i + 0, j + 1), 1.0 * weight);
00431       m_solver.K (row, grc2gl (i - 1, j + 0), 1.0 * weight);
00432       m_solver.K (row, grc2gl (i + 1, j + 0), 1.0 * weight);
00433 
00434       row++;
00435     }
00436   }
00437 }
00438 
00439 void
00440 FittingCylinder::addCageBoundaryRegularisation (double weight, int side, unsigned &row)
00441 {
00442   int cp_red = (m_nurbs.m_order[1] - 2);
00443   int i = 0;
00444   int j = 0;
00445 
00446   switch (side)
00447   {
00448     case EAST:
00449       i = m_nurbs.m_cv_count[0] - 1;
00450     case WEST:
00451       for (j = 1; j < (m_nurbs.m_cv_count[1] - 2 * cp_red) + 1; j++)
00452       {
00453 
00454         m_solver.f (row, 0, 0.0);
00455         m_solver.f (row, 1, 0.0);
00456         m_solver.f (row, 2, 0.0);
00457 
00458         m_solver.K (row, grc2gl (i, j + 0), -2.0 * weight);
00459         m_solver.K (row, grc2gl (i, j - 1), 1.0 * weight);
00460         m_solver.K (row, grc2gl (i, j + 1), 1.0 * weight);
00461 
00462         row++;
00463       }
00464       break;
00465   }
00466 }
00467 
00468 Vector2d
00469 FittingCylinder::inverseMapping (const ON_NurbsSurface &nurbs, const Vector3d &pt, const Vector2d &hint, double &error,
00470                                  Vector3d &p, Vector3d &tu, Vector3d &tv, int maxSteps, double accuracy, bool quiet)
00471 {
00472 
00473   double pointAndTangents[9];
00474 
00475   Vector2d current, delta;
00476   Matrix2d A;
00477   Vector2d b;
00478   Vector3d r;
00479   std::vector<double> elementsU = getElementVector (nurbs, 0);
00480   std::vector<double> elementsV = getElementVector (nurbs, 1);
00481   double minU = elementsU[0];
00482   double minV = elementsV[0];
00483   double maxU = elementsU[elementsU.size () - 1];
00484   double maxV = elementsV[elementsV.size () - 1];
00485 
00486   current = hint;
00487 
00488   for (int k = 0; k < maxSteps; k++)
00489   {
00490 
00491     nurbs.Evaluate (current (0), current (1), 1, 3, pointAndTangents);
00492     p (0) = pointAndTangents[0];
00493     p (1) = pointAndTangents[1];
00494     p (2) = pointAndTangents[2];
00495     tu (0) = pointAndTangents[3];
00496     tu (1) = pointAndTangents[4];
00497     tu (2) = pointAndTangents[5];
00498     tv (0) = pointAndTangents[6];
00499     tv (1) = pointAndTangents[7];
00500     tv (2) = pointAndTangents[8];
00501 
00502     r = p - pt;
00503 
00504     b (0) = -r.dot (tu);
00505     b (1) = -r.dot (tv);
00506 
00507     A (0, 0) = tu.dot (tu);
00508     A (0, 1) = tu.dot (tv);
00509     A (1, 0) = A (0, 1);
00510     A (1, 1) = tv.dot (tv);
00511 
00512     delta = A.ldlt ().solve (b);
00513 
00514     if (delta.norm () < accuracy)
00515     {
00516 
00517       error = r.norm ();
00518       return current;
00519 
00520     }
00521     else
00522     {
00523       current = current + delta;
00524       if (current (0) < minU)
00525         current (0) = minU;
00526       else if (current (0) > maxU)
00527         current (0) = maxU;
00528 
00529       if (current (1) < minV)
00530         current (1) = maxV - (minV - current (1));
00531       else if (current (1) > maxV)
00532         current (1) = minV + (current (1) - maxV);
00533     }
00534 
00535   }
00536 
00537   error = r.norm ();
00538 
00539   if (!quiet)
00540   {
00541     printf ("[FittingCylinder::inverseMapping] Warning: Method did not converge (%e %d)\n", accuracy, maxSteps);
00542     printf ("  %f %f ... %f %f\n", hint (0), hint (1), current (0), current (1));
00543   }
00544 
00545   return current;
00546 }
00547 
00548 Vector2d
00549 FittingCylinder::findClosestElementMidPoint (const ON_NurbsSurface &nurbs, const Vector3d &pt)
00550 {
00551   Vector2d hint;
00552   Vector3d r;
00553   std::vector<double> elementsU = getElementVector (nurbs, 0);
00554   std::vector<double> elementsV = getElementVector (nurbs, 1);
00555 
00556   double d_shortest = std::numeric_limits<double>::max ();
00557   for (unsigned i = 0; i < elementsU.size () - 1; i++)
00558   {
00559     for (unsigned j = 0; j < elementsV.size () - 1; j++)
00560     {
00561       double points[3];
00562 
00563       double xi = elementsU[i] + 0.5 * (elementsU[i + 1] - elementsU[i]);
00564       double eta = elementsV[j] + 0.5 * (elementsV[j + 1] - elementsV[j]);
00565 
00566       nurbs.Evaluate (xi, eta, 0, 3, points);
00567       r (0) = points[0] - pt (0);
00568       r (1) = points[1] - pt (1);
00569       r (2) = points[2] - pt (2);
00570 
00571       double d = r.squaredNorm ();
00572 
00573       if ((i == 0 && j == 0) || d < d_shortest)
00574       {
00575         d_shortest = d;
00576         hint (0) = xi;
00577         hint (1) = eta;
00578       }
00579     }
00580   }
00581 
00582   return hint;
00583 }
00584 


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