fitting_curve_2d_atdm.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_atdm.h>
00039 #include <stdexcept>
00040 
00041 using namespace pcl;
00042 using namespace on_nurbs;
00043 
00044 FittingCurve2dATDM::FittingCurve2dATDM (int order, NurbsDataCurve2d *data) :
00045   FittingCurve2dAPDM (order, data)
00046 {
00047 }
00048 
00049 FittingCurve2dATDM::FittingCurve2dATDM (NurbsDataCurve2d *data, const ON_NurbsCurve &ns) :
00050   FittingCurve2dAPDM (data, ns)
00051 {
00052 }
00053 
00054 void
00055 FittingCurve2dATDM::assemble (const FittingCurve2dAPDM::Parameter &parameter)
00056 {
00057   int cp_red = m_nurbs.m_order - 2;
00058   int ncp = m_nurbs.m_cv_count - 2 * cp_red;
00059   int nCageReg = m_nurbs.m_cv_count - 2 * cp_red;
00060   int nInt = int (m_data->interior.size ());
00061   //  int nCommon = m_data->common.size();
00062   //  int nClosestP = parameter.closest_point_resolution;
00063 
00064   std::vector<double> elements = getElementVector (m_nurbs);
00065   int nClosestP = int (elements.size ());
00066 
00067   double wInt = 1.0;
00068   if (!m_data->interior_weight.empty ())
00069   {
00070     wInt = m_data->interior_weight[0];
00071   }
00072 
00073   double wCageReg = parameter.smoothness;
00074 
00075   unsigned nrows = 2 * nInt + 2 * nCageReg + 2 * nClosestP;
00076 
00077   m_solver.assign (nrows, ncp * 2, 1);
00078 
00079   unsigned row (0);
00080 
00081   if (wInt > 0.0)
00082     assembleInterior (wInt, parameter.interior_sigma2, parameter.rScale, row);
00083 
00084   assembleClosestPoints (elements, parameter.closest_point_weight, parameter.closest_point_sigma2, row);
00085 
00086   if (wCageReg > 0.0)
00087     addCageRegularisation (wCageReg, row, elements, parameter.smooth_concavity);
00088 
00089   if (row < nrows)
00090   {
00091     m_solver.resize (row);
00092     if (!m_quiet)
00093       printf ("[FittingCurve2dATDM::assemble] Warning: rows do not match: %d %d\n", row, nrows);
00094   }
00095 }
00096 
00097 double
00098 FittingCurve2dATDM::solve (double damp)
00099 {
00100   double cps_diff (0.0);
00101 
00102   if (m_solver.solve ())
00103     cps_diff = updateCurve (damp);
00104 
00105   return cps_diff;
00106 }
00107 
00108 double
00109 FittingCurve2dATDM::updateCurve (double damp)
00110 {
00111   int cp_red = m_nurbs.m_order - 2;
00112   int ncp = m_nurbs.m_cv_count - 2 * cp_red;
00113 
00114   double cps_diff (0.0);
00115 
00116   for (int j = 0; j < ncp; j++)
00117   {
00118 
00119     ON_3dPoint cp_prev;
00120     m_nurbs.GetCV (j, cp_prev);
00121 
00122     double x = m_solver.x (2 * j + 0, 0);
00123     double y = m_solver.x (2 * j + 1, 0);
00124 
00125     cps_diff += sqrt ((x - cp_prev.x) * (x - cp_prev.x) + (y - cp_prev.y) * (y - cp_prev.y));
00126 
00127     ON_3dPoint cp;
00128     cp.x = cp_prev.x + damp * (x - cp_prev.x);
00129     cp.y = cp_prev.y + damp * (y - cp_prev.y);
00130     cp.z = 0.0;
00131 
00132     m_nurbs.SetCV (j, cp);
00133   }
00134 
00135   for (int j = 0; j < 2 * cp_red; j++)
00136   {
00137     ON_3dPoint cp;
00138     m_nurbs.GetCV (2 * cp_red - 1 - j, cp);
00139     m_nurbs.SetCV (m_nurbs.m_cv_count - 1 - j, cp);
00140   }
00141 
00142   return cps_diff / ncp;
00143 }
00144 
00145 void
00146 FittingCurve2dATDM::addPointConstraint (const double &param, const Eigen::Vector2d &point,
00147                                         const Eigen::Vector2d &normal, double weight, unsigned &row)
00148 {
00149   int cp_red = m_nurbs.m_order - 2;
00150   int ncp = m_nurbs.m_cv_count - 2 * cp_red;
00151   double *N = new double[m_nurbs.m_order * m_nurbs.m_order];
00152 
00153   int E = ON_NurbsSpanIndex (m_nurbs.m_order, m_nurbs.m_cv_count, m_nurbs.m_knot, param, 0, 0);
00154 
00155   ON_EvaluateNurbsBasis (m_nurbs.m_order, m_nurbs.m_knot + E, param, N);
00156 
00157   // X
00158   m_solver.f (row, 0, normal (0) * point (0) * weight);
00159   for (int i = 0; i < m_nurbs.m_order; i++)
00160     m_solver.K (row, 2 * ((E + i) % ncp) + 0, weight * normal (0) * N[i]);
00161   row++;
00162 
00163   // Y
00164   m_solver.f (row, 0, normal (1) * point (1) * weight);
00165   for (int i = 0; i < m_nurbs.m_order; i++)
00166     m_solver.K (row, 2 * ((E + i) % ncp) + 1, weight * normal (1) * N[i]);
00167   row++;
00168 
00169   delete[] N;
00170 }
00171 
00172 void
00173 FittingCurve2dATDM::addCageRegularisation (double weight, unsigned &row, const std::vector<double> &elements,
00174                                            double wConcav)
00175 {
00176   int cp_red = (m_nurbs.m_order - 2);
00177   int ncp = (m_nurbs.m_cv_count - 2 * cp_red);
00178 
00179   //  m_data->interior_line_start.clear();
00180   //  m_data->interior_line_end.clear();
00181   for (int j = 1; j < ncp + 1; j++)
00182   {
00183 
00184     if (wConcav == 0.0)
00185     {
00186     }
00187     else
00188     {
00189       int i = j % ncp;
00190 
00191       if (i >= int (m_data->closest_points_error.size () - 1))
00192       {
00193         printf ("[FittingCurve2dATDM::addCageRegularisation] Warning, index for closest_points_error out of bounds\n");
00194       }
00195       else
00196       {
00197         Eigen::Vector2d t, n;
00198         double pt[4];
00199 
00200         double xi = elements[i] + 0.5 * (elements[i + 1] - elements[i]);
00201         m_nurbs.Evaluate (xi, 1, 2, pt);
00202         t (0) = pt[2];
00203         t (1) = pt[3];
00204         n (0) = -t (1);
00205         n (1) = t (0);
00206         n.normalize ();
00207 
00208         double err = m_data->closest_points_error[i] + 0.5 * (m_data->closest_points_error[i + 1]
00209             - m_data->closest_points_error[i]);
00210         m_solver.f (row + 0, 0, err * wConcav * n (0));
00211         m_solver.f (row + 1, 0, err * wConcav * n (1));
00212 
00213         //        Eigen::Vector2d p1, p2;
00214         //        p1(0) = pt[0];
00215         //        p1(1) = pt[1];
00216         //        p2 = p1 + n * wConcav * err;
00217         //        m_data->interior_line_start.push_back(p1);
00218         //        m_data->interior_line_end.push_back(p2);
00219       }
00220     }
00221 
00222     m_solver.K (row, 2 * ((j + 0) % ncp) + 0, -2.0 * weight);
00223     m_solver.K (row, 2 * ((j - 1) % ncp) + 0, 1.0 * weight);
00224     m_solver.K (row, 2 * ((j + 1) % ncp) + 0, 1.0 * weight);
00225     row++;
00226 
00227     m_solver.K (row, 2 * ((j + 0) % ncp) + 1, -2.0 * weight);
00228     m_solver.K (row, 2 * ((j - 1) % ncp) + 1, 1.0 * weight);
00229     m_solver.K (row, 2 * ((j + 1) % ncp) + 1, 1.0 * weight);
00230     row++;
00231   }
00232 }
00233 
00234 void
00235 FittingCurve2dATDM::assembleInterior (double wInt, double sigma2, double rScale, unsigned &row)
00236 {
00237   int nInt = int (m_data->interior.size ());
00238   bool wFunction (true);
00239   double ds = 1.0 / (2.0 * sigma2);
00240   m_data->interior_line_start.clear ();
00241   m_data->interior_line_end.clear ();
00242   m_data->interior_error.clear ();
00243   m_data->interior_normals.clear ();
00244   for (int p = 0; p < nInt; p++)
00245   {
00246     Eigen::Vector2d &pcp = m_data->interior[p];
00247 
00248     // inverse mapping
00249     double param;
00250     Eigen::Vector2d pt, t, n;
00251     double error;
00252     if (p < int (m_data->interior_param.size ()))
00253     {
00254       param = findClosestElementMidPoint (m_nurbs, pcp, m_data->interior_param[p]);
00255       param = inverseMapping (m_nurbs, pcp, param, error, pt, t, rScale, in_max_steps, in_accuracy, m_quiet);
00256       m_data->interior_param[p] = param;
00257     }
00258     else
00259     {
00260       param = findClosestElementMidPoint (m_nurbs, pcp);
00261       param = inverseMapping (m_nurbs, pcp, param, error, pt, t, rScale, in_max_steps, in_accuracy, m_quiet);
00262       m_data->interior_param.push_back (param);
00263     }
00264 
00265     m_data->interior_error.push_back (error);
00266 
00267     double pointAndTangents[6];
00268     m_nurbs.Evaluate (param, 2, 2, pointAndTangents);
00269     pt (0) = pointAndTangents[0];
00270     pt (1) = pointAndTangents[1];
00271     t (0) = pointAndTangents[2];
00272     t (1) = pointAndTangents[3];
00273     n (0) = pointAndTangents[4];
00274     n (1) = pointAndTangents[5];
00275 
00276     // evaluate if point lies inside or outside the closed curve
00277     Eigen::Vector3d a (pcp (0) - pt (0), pcp (1) - pt (1), 0.0);
00278     Eigen::Vector3d b (t (0), t (1), 0.0);
00279     Eigen::Vector3d z = a.cross (b);
00280 
00281     if (p < int (m_data->interior_weight.size ()))
00282       wInt = m_data->interior_weight[p];
00283 
00284     if (p < int (m_data->interior_weight_function.size ()))
00285       wFunction = m_data->interior_weight_function[p];
00286 
00287     double w (wInt);
00288     if (z (2) > 0.0 && wFunction)
00289       w = wInt * exp (-(error * error) * ds);
00290 
00291     n.normalize ();
00292     //    m_data->interior_line_start.push_back(pt);
00293     //    m_data->interior_line_end.push_back(pt + n * 0.01);
00294 
00295     //      w = 0.5 * wInt * exp(-(error * error) * ds);
00296 
00297     // evaluate if this point is the closest point
00298     //    int idx = NurbsTools::getClosestPoint(pt, m_data->interior);
00299     //    if(idx == p)
00300     //      w = 2.0 * wInt;
00301 
00302     if (w > 1e-6) // avoids ill-conditioned matrix
00303       addPointConstraint (m_data->interior_param[p], m_data->interior[p], n, w, row);
00304     else
00305     {
00306       //      m_solver.K(row, 0, 0.0);
00307       //      row++;
00308     }
00309   }
00310 }
00311 
00312 void
00313 FittingCurve2dATDM::assembleClosestPoints (const std::vector<double> &elements, double weight, double sigma2,
00314                                            unsigned &row)
00315 {
00316   m_data->closest_points.clear ();
00317   m_data->closest_points_param.clear ();
00318   m_data->closest_points_error.clear ();
00319   m_data->interior_line_start.clear ();
00320   m_data->interior_line_end.clear ();
00321 
00322   double ds = 1.0 / (2.0 * sigma2);
00323 
00324   for (unsigned i = 0; i < elements.size (); i++)
00325   {
00326 
00327     int j = i % int (elements.size ());
00328 
00329     double dxi = elements[j] - elements[i];
00330     double xi = elements[i] + 0.5 * dxi;
00331 
00332     double points[6];
00333     Eigen::Vector2d p1, p2, p3, t, in, n;
00334     m_nurbs.Evaluate (xi, 2, 2, points);
00335     p1 (0) = points[0];
00336     p1 (1) = points[1];
00337     t (0) = points[2];
00338     t (1) = points[3];
00339     t.normalize ();
00340     in (0) = t (1);
00341     in (1) = -t (0);
00342 
00343     n (0) = points[4] * 0.01;
00344     n (1) = points[5] * 0.01;
00345 
00346     n = in * in.dot (n);
00347 
00348     unsigned idxcp;
00349     unsigned idx = NurbsTools::getClosestPoint (p1, in, m_data->interior, idxcp);
00350     p2 = m_data->interior[idx];
00351     p3 = m_data->interior[idxcp];
00352 
00353     //    double xi2 = m_data->interior_param[idx];
00354 
00355     double error2 = (p2 - p1).squaredNorm ();
00356 
00357     m_data->closest_points.push_back (p3);
00358     m_data->closest_points_param.push_back (xi);
00359     m_data->closest_points_error.push_back ((p3 - p1).squaredNorm ());
00360 
00361     double w (weight);
00362     w = 0.5 * weight * exp (-(error2) * ds);
00363     //    w = weight * std::fabs(in.dot(p2-p1));
00364 
00365     //    if (weight > 0.0 && (std::fabs(xi2 - xi) < std::fabs(dxi)))
00366     if (w > 0.0)
00367     {
00368       addPointConstraint (xi, p2, n, w, row);
00369       m_data->interior_line_start.push_back (p1);
00370       m_data->interior_line_end.push_back (p2);
00371     }
00372 
00373   }
00374 }
00375 
00376 void
00377 FittingCurve2dATDM::assembleClosestPoints (int res, double weight, unsigned &row)
00378 {
00379   std::vector<double> elements = FittingCurve2dATDM::getElementVector (m_nurbs);
00380   double xi_min = elements.front ();
00381   double xi_max = elements.back ();
00382 
00383   double step = (xi_max - xi_min) / res;
00384 
00385   //  m_data->interior_line_start.clear();
00386   //  m_data->interior_line_end.clear();
00387   m_data->closest_points.clear ();
00388   m_data->closest_points_param.clear ();
00389   m_data->closest_points_error.clear ();
00390   for (int i = 0; i < res; i++)
00391   {
00392     double xi = xi_min + i * step;
00393 
00394     double points[6];
00395     Eigen::Vector2d p1, p2, t, in, n;
00396     //    m_nurbs.Evaluate(xi, 0, 2, points);
00397     //    p1(0) = points[0];
00398     //    p1(1) = points[1];
00399 
00400     m_nurbs.Evaluate (xi, 2, 2, points);
00401     p1 (0) = points[0];
00402     p1 (1) = points[1];
00403     t (0) = points[2];
00404     t (1) = points[3];
00405     in (0) = t (1);
00406     in (1) = -t (0);
00407     n (0) = points[4];
00408     n (1) = points[5];
00409     n = in * in.dot (n);
00410 
00411     unsigned idx = NurbsTools::getClosestPoint (p1, m_data->interior);
00412     p2 = m_data->interior[idx];
00413 
00414     m_data->closest_points.push_back (p2);
00415     m_data->closest_points_param.push_back (xi);
00416     m_data->closest_points_error.push_back ((p2 - p1).squaredNorm ());
00417     //    m_data->interior_line_start.push_back(p1);
00418     //    m_data->interior_line_end.push_back(p2);
00419 
00420     addPointConstraint (xi, p2, n, weight, row);
00421 
00422   }
00423 }


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