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


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