fitting_curve_2d_sdm.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_sdm.h>
00039 #include <stdexcept>
00040 
00041 using namespace pcl;
00042 using namespace on_nurbs;
00043 
00044 FittingCurve2dSDM::FittingCurve2dSDM (int order, NurbsDataCurve2d *data) :
00045   FittingCurve2dPDM (order, data)
00046 {
00047 
00048 }
00049 
00050 FittingCurve2dSDM::FittingCurve2dSDM (NurbsDataCurve2d *data, const ON_NurbsCurve &ns) :
00051   FittingCurve2dPDM (data, ns)
00052 {
00053 
00054 }
00055 
00056 void
00057 FittingCurve2dSDM::assemble (const FittingCurve2dPDM::Parameter &parameter)
00058 {
00059   int cp_red = m_nurbs.m_order - 2;
00060   int ncp = m_nurbs.m_cv_count - 2 * cp_red;
00061   int nCageReg = m_nurbs.m_cv_count - 2 * cp_red;
00062   int nInt = int (m_data->interior.size ());
00063 
00064   double wInt = 1.0;
00065   if (!m_data->interior_weight.empty ())
00066     wInt = m_data->interior_weight[0];
00067 
00068   unsigned nrows = 4 * nInt + 2 * nCageReg;
00069 
00070   m_solver.assign (nrows, ncp * 2, 1);
00071 
00072   unsigned row (0);
00073 
00074   if (wInt > 0.0)
00075     assembleInterior (wInt, parameter.rScale, row);
00076 
00077   if (parameter.smoothness > 0.0)
00078     addCageRegularisation (parameter.smoothness, row);
00079 
00080   if (row < nrows)
00081   {
00082     m_solver.resize (row);
00083     if (!m_quiet)
00084       printf ("[FittingCurve2dSDM::assemble] Warning: rows do not match: %d %d\n", row, nrows);
00085   }
00086 }
00087 
00088 double
00089 FittingCurve2dSDM::solve (double damp)
00090 {
00091   double cps_diff (0.0);
00092 
00093   if (m_solver.solve ())
00094     cps_diff = updateCurve (damp);
00095 
00096   return cps_diff;
00097 }
00098 
00099 double
00100 FittingCurve2dSDM::updateCurve (double damp)
00101 {
00102   int cp_red = m_nurbs.m_order - 2;
00103   int ncp = m_nurbs.m_cv_count - 2 * cp_red;
00104 
00105   double cps_diff (0.0);
00106 
00107   // TODO this implementation rotates the control points, look up fitting_curve_2d_apdm for correct implementation
00108 
00109   for (int j = 0; j < ncp; j++)
00110   {
00111 
00112     ON_3dPoint cp_prev;
00113     m_nurbs.GetCV (j + cp_red, cp_prev);
00114 
00115     double x = m_solver.x (2 * j + 0, 0);
00116     double y = m_solver.x (2 * j + 1, 0);
00117 
00118     cps_diff += sqrt ((x - cp_prev.x) * (x - cp_prev.x) + (y - cp_prev.y) * (y - cp_prev.y));
00119 
00120     ON_3dPoint cp;
00121     cp.x = cp_prev.x + damp * (x - cp_prev.x);
00122     cp.y = cp_prev.y + damp * (y - cp_prev.y);
00123     cp.z = 0.0;
00124 
00125     m_nurbs.SetCV (j + cp_red, cp);
00126   }
00127 
00128   for (int j = 0; j < cp_red; j++)
00129   {
00130 
00131     ON_3dPoint cp;
00132     m_nurbs.GetCV (m_nurbs.m_cv_count - 1 - cp_red + j, cp);
00133     m_nurbs.SetCV (j, cp);
00134 
00135     m_nurbs.GetCV (cp_red - j, cp);
00136     m_nurbs.SetCV (m_nurbs.m_cv_count - 1 - j, cp);
00137   }
00138   return cps_diff / ncp;
00139 }
00140 
00141 void
00142 FittingCurve2dSDM::addPointConstraint (const double &param, const Eigen::Vector2d &point,
00143                                        const Eigen::Vector2d &normal, const Eigen::Vector2d &tangent, double rho,
00144                                        double d, double weight, unsigned &row)
00145 {
00146   int cp_red = m_nurbs.m_order - 2;
00147   int ncp = m_nurbs.m_cv_count - 2 * cp_red;
00148   double *N = new double[m_nurbs.m_order * m_nurbs.m_order];
00149 
00150   int E = ON_NurbsSpanIndex (m_nurbs.m_order, m_nurbs.m_cv_count, m_nurbs.m_knot, param, 0, 0);
00151 
00152   ON_EvaluateNurbsBasis (m_nurbs.m_order, m_nurbs.m_knot + E, param, N);
00153 
00154   m_solver.f (row, 0, normal (0) * point (0) * weight);
00155   for (int i = 0; i < m_nurbs.m_order; i++)
00156   {
00157     m_solver.K (row, 2 * ((E + i) % ncp) + 0, weight * normal (0) * N[i]);
00158   }
00159   row++;
00160 
00161   m_solver.f (row, 0, normal (1) * point (1) * weight);
00162   for (int i = 0; i < m_nurbs.m_order; i++)
00163   {
00164     m_solver.K (row, 2 * ((E + i) % ncp) + 1, weight * normal (1) * N[i]);
00165   }
00166   row++;
00167 
00168   //  if (d >= 0.0 && d > rho)
00169   //    printf("[FittingCurve2dSDM::addPointConstraint] Warning d > rho: %f > %f\n", d, rho);
00170 
00171   if (d < 0.0)
00172   {
00173 
00174     double a = d / (d - rho);
00175 
00176     m_solver.f (row, 0, a * a * tangent (0) * point (0) * weight);
00177     for (int i = 0; i < m_nurbs.m_order; i++)
00178       m_solver.K (row, 2 * ((E + i) % ncp) + 0, a * a * weight * tangent (0) * N[i]);
00179     row++;
00180 
00181     m_solver.f (row, 0, a * a * tangent (1) * point (1) * weight);
00182     for (int i = 0; i < m_nurbs.m_order; i++)
00183       m_solver.K (row, 2 * ((E + i) % ncp) + 1, a * a * weight * tangent (1) * N[i]);
00184     row++;
00185 
00186   }
00187 
00188   delete [] N;
00189 }
00190 
00191 void
00192 FittingCurve2dSDM::addCageRegularisation (double weight, unsigned &row)
00193 {
00194   int cp_red = (m_nurbs.m_order - 2);
00195   int ncp = (m_nurbs.m_cv_count - 2 * cp_red);
00196 
00197   for (int j = 1; j < ncp + 1; j++)
00198   {
00199     m_solver.K (row, 2 * ((j + 0) % ncp) + 0, -2.0 * weight);
00200     m_solver.K (row, 2 * ((j - 1) % ncp) + 0, 1.0 * weight);
00201     m_solver.K (row, 2 * ((j + 1) % ncp) + 0, 1.0 * weight);
00202     row++;
00203 
00204     m_solver.K (row, 2 * ((j + 0) % ncp) + 1, -2.0 * weight);
00205     m_solver.K (row, 2 * ((j - 1) % ncp) + 1, 1.0 * weight);
00206     m_solver.K (row, 2 * ((j + 1) % ncp) + 1, 1.0 * weight);
00207     row++;
00208   }
00209 }
00210 
00211 void
00212 FittingCurve2dSDM::assembleInterior (double wInt, double rScale, unsigned &row)
00213 {
00214   unsigned nInt = int (m_data->interior.size ());
00215   m_data->interior_line_start.clear ();
00216   m_data->interior_line_end.clear ();
00217   m_data->interior_error.clear ();
00218   m_data->interior_normals.clear ();
00219 
00220   unsigned updateTNR (false);
00221   if (m_data->interior_ncps_prev != m_nurbs.CVCount ())
00222   {
00223     if (!m_quiet)
00224       printf ("[FittingCurve2dSDM::assembleInterior] updating T, N, rho\n");
00225     m_data->interior_tangents.clear ();
00226     m_data->interior_normals.clear ();
00227     m_data->interior_rho.clear ();
00228     m_data->interior_ncps_prev = m_nurbs.CVCount ();
00229     updateTNR = true;
00230   }
00231 
00232   for (unsigned p = 0; p < nInt; p++)
00233   {
00234     Eigen::Vector2d &pcp = m_data->interior[p];
00235 
00236     // inverse mapping
00237     double param;
00238     Eigen::Vector2d pt, t, n;
00239     double error;
00240     if (p < int (m_data->interior_param.size ()))
00241     {
00242       param = findClosestElementMidPoint (m_nurbs, pcp, m_data->interior_param[p]);
00243       param = inverseMapping (m_nurbs, pcp, param, error, pt, t, rScale, in_max_steps, in_accuracy, m_quiet);
00244       m_data->interior_param[p] = param;
00245     }
00246     else
00247     {
00248       param = findClosestElementMidPoint (m_nurbs, pcp);
00249       param = inverseMapping (m_nurbs, pcp, param, error, pt, t, rScale, in_max_steps, in_accuracy, m_quiet);
00250       m_data->interior_param.push_back (param);
00251     }
00252 
00253     m_data->interior_error.push_back (error);
00254 
00255     double dt, kappa, rho, rho_prev;
00256     Eigen::Vector2d n_prev, t_prev;
00257 
00258     double pointAndTangents[6];
00259     m_nurbs.Evaluate (param, 2, 2, pointAndTangents);
00260     pt (0) = pointAndTangents[0];
00261     pt (1) = pointAndTangents[1];
00262     t (0) = pointAndTangents[2];
00263     t (1) = pointAndTangents[3];
00264     n (0) = pointAndTangents[4];
00265     n (1) = pointAndTangents[5];
00266 
00267     dt = t.norm ();
00268     t /= dt;
00269     Eigen::Vector2d in (t (1), -t (0));
00270     n /= dt; // TODO something is wrong with the normal from nurbs.Evaluate(...)
00271     n = in * in.dot (n);
00272 
00273     kappa = n.norm ();
00274     rho = (1.0 / kappa);
00275     n *= rho;
00276 
00277     if (!updateTNR && m_data->interior_rho.size () == nInt)
00278     {
00279       n_prev = m_data->interior_normals[p];
00280       t_prev = m_data->interior_tangents[p];
00281       rho_prev = m_data->interior_rho[p];
00282       //        m_data->interior_normals[p] = n;
00283       //        m_data->interior_tangents[p] = t;
00284       //        m_data->interior_rho[p] = rho;
00285     }
00286     else
00287     {
00288       m_data->interior_tangents.push_back (t);
00289       m_data->interior_normals.push_back (n);
00290       m_data->interior_rho.push_back (rho);
00291       n_prev = n;
00292       t_prev = t;
00293       rho_prev = rho;
00294     }
00295 
00296     // signed distance
00297     double d;
00298     if ((pcp - pt).dot (n) >= 0.0)
00299       d = (pcp - pt).norm ();
00300     else
00301       d = -(pcp - pt).norm ();
00302 
00303     if (p < m_data->interior_weight.size ())
00304       wInt = m_data->interior_weight[p];
00305 
00306     m_data->interior_line_start.push_back (pt);
00307     m_data->interior_line_end.push_back (pcp);
00308 
00309     addPointConstraint (m_data->interior_param[p], m_data->interior[p], n_prev, t_prev, rho_prev, d, wInt, row);
00310   }
00311 
00312   //  printf("[FittingCurve2dSDM::assembleInterior] d>0: %d d<0: %d\n", i1, i2);
00313 }


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