fitting_curve_2d_tdm.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_tdm.h>
00039 #include <stdexcept>
00040 
00041 using namespace pcl;
00042 using namespace on_nurbs;
00043 
00044 FittingCurve2dTDM::FittingCurve2dTDM (int order, NurbsDataCurve2d *data) :
00045   FittingCurve2dPDM (order, data)
00046 {
00047 }
00048 
00049 FittingCurve2dTDM::FittingCurve2dTDM (NurbsDataCurve2d *data, const ON_NurbsCurve &ns) :
00050   FittingCurve2dPDM (data, ns)
00051 {
00052 }
00053 
00054 void
00055 FittingCurve2dTDM::assemble (const FittingCurve2dPDM::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 
00062   double wInt = 1.0;
00063   if (!m_data->interior_weight.empty ())
00064     wInt = m_data->interior_weight[0];
00065 
00066   unsigned nrows = 2 * nInt + 2 * nCageReg;
00067 
00068   m_solver.assign (nrows, ncp * 2, 1);
00069 
00070   unsigned row (0);
00071 
00072   if (wInt > 0.0)
00073     assembleInterior (wInt, parameter.rScale, row);
00074 
00075   if (parameter.smoothness > 0.0)
00076     addCageRegularisation (parameter.smoothness, row);
00077 
00078   if (row < nrows)
00079   {
00080     m_solver.resize (row);
00081     if (!m_quiet)
00082       printf ("[FittingCurve2dTDM::assemble] Warning: rows do not match: %d %d\n", row, nrows);
00083   }
00084 }
00085 
00086 double
00087 FittingCurve2dTDM::solve (double damp)
00088 {
00089   double cps_diff (0.0);
00090 
00091   if (m_solver.solve ())
00092     cps_diff = updateCurve (damp);
00093 
00094   return cps_diff;
00095 }
00096 
00097 double
00098 FittingCurve2dTDM::updateCurve (double damp)
00099 {
00100   int cp_red = m_nurbs.m_order - 2;
00101   int ncp = m_nurbs.m_cv_count - 2 * cp_red;
00102 
00103   double cps_diff (0.0);
00104 
00105   // TODO this implementation rotates the control points, look up fitting_curve_2d_apdm for correct implementation
00106 
00107   for (int j = 0; j < ncp; j++)
00108   {
00109 
00110     ON_3dPoint cp_prev;
00111     m_nurbs.GetCV (j + cp_red, cp_prev);
00112 
00113     double x = m_solver.x (2 * j + 0, 0);
00114     double y = m_solver.x (2 * j + 1, 0);
00115 
00116     cps_diff += sqrt ((x - cp_prev.x) * (x - cp_prev.x) + (y - cp_prev.y) * (y - cp_prev.y));
00117 
00118     ON_3dPoint cp;
00119     cp.x = cp_prev.x + damp * (x - cp_prev.x);
00120     cp.y = cp_prev.y + damp * (y - cp_prev.y);
00121     cp.z = 0.0;
00122 
00123     m_nurbs.SetCV (j + cp_red, cp);
00124   }
00125 
00126   for (int j = 0; j < cp_red; j++)
00127   {
00128 
00129     ON_3dPoint cp;
00130     m_nurbs.GetCV (m_nurbs.m_cv_count - 1 - cp_red + j, cp);
00131     m_nurbs.SetCV (j, cp);
00132 
00133     m_nurbs.GetCV (cp_red - j, cp);
00134     m_nurbs.SetCV (m_nurbs.m_cv_count - 1 - j, cp);
00135   }
00136   return cps_diff / ncp;
00137 }
00138 
00139 void
00140 FittingCurve2dTDM::addPointConstraint (const double &param, const Eigen::Vector2d &point,
00141                                         const Eigen::Vector2d &normal, double weight, unsigned &row)
00142 {
00143   int cp_red = m_nurbs.m_order - 2;
00144   int ncp = m_nurbs.m_cv_count - 2 * cp_red;
00145   double *N = new double[m_nurbs.m_order * m_nurbs.m_order];
00146 
00147   int E = ON_NurbsSpanIndex (m_nurbs.m_order, m_nurbs.m_cv_count, m_nurbs.m_knot, param, 0, 0);
00148 
00149   ON_EvaluateNurbsBasis (m_nurbs.m_order, m_nurbs.m_knot + E, param, N);
00150 
00151   // X
00152   m_solver.f (row, 0, normal (0) * point (0) * weight);
00153   for (int i = 0; i < m_nurbs.m_order; i++)
00154     m_solver.K (row, 2 * ((E + i) % ncp) + 0, weight * normal (0) * N[i]);
00155   row++;
00156 
00157   // Y
00158   m_solver.f (row, 0, normal (1) * point (1) * weight);
00159   for (int i = 0; i < m_nurbs.m_order; i++)
00160     m_solver.K (row, 2 * ((E + i) % ncp) + 1, weight * normal (1) * N[i]);
00161   row++;
00162 
00163   delete [] N;
00164 }
00165 
00166 void
00167 FittingCurve2dTDM::addCageRegularisation (double weight, unsigned &row)
00168 {
00169   int cp_red = (m_nurbs.m_order - 2);
00170   int ncp = (m_nurbs.m_cv_count - 2 * cp_red);
00171 
00172   //  m_data->interior_line_start.clear();
00173   //  m_data->interior_line_end.clear();
00174   for (int j = 1; j < ncp + 1; j++)
00175   {
00176 
00177     m_solver.K (row, 2 * ((j + 0) % ncp) + 0, -2.0 * weight);
00178     m_solver.K (row, 2 * ((j - 1) % ncp) + 0, 1.0 * weight);
00179     m_solver.K (row, 2 * ((j + 1) % ncp) + 0, 1.0 * weight);
00180     row++;
00181 
00182     m_solver.K (row, 2 * ((j + 0) % ncp) + 1, -2.0 * weight);
00183     m_solver.K (row, 2 * ((j - 1) % ncp) + 1, 1.0 * weight);
00184     m_solver.K (row, 2 * ((j + 1) % ncp) + 1, 1.0 * weight);
00185     row++;
00186   }
00187 }
00188 
00189 void
00190 FittingCurve2dTDM::assembleInterior (double wInt, double rScale, unsigned &row)
00191 {
00192   int nInt = int (m_data->interior.size ());
00193   m_data->interior_line_start.clear ();
00194   m_data->interior_line_end.clear ();
00195   m_data->interior_error.clear ();
00196   m_data->interior_normals.clear ();
00197   for (int p = 0; p < nInt; p++)
00198   {
00199     Eigen::Vector2d &pcp = m_data->interior[p];
00200 
00201     // inverse mapping
00202     double param;
00203     Eigen::Vector2d pt, t, n;
00204     double error;
00205     if (p < int (m_data->interior_param.size ()))
00206     {
00207       param = findClosestElementMidPoint (m_nurbs, pcp, m_data->interior_param[p]);
00208       param = inverseMapping (m_nurbs, pcp, param, error, pt, t, rScale, in_max_steps, in_accuracy, m_quiet);
00209       m_data->interior_param[p] = param;
00210     }
00211     else
00212     {
00213       param = findClosestElementMidPoint (m_nurbs, pcp);
00214       param = inverseMapping (m_nurbs, pcp, param, error, pt, t, rScale, in_max_steps, in_accuracy, m_quiet);
00215       m_data->interior_param.push_back (param);
00216     }
00217 
00218     m_data->interior_error.push_back (error);
00219 
00220     double pointAndTangents[6];
00221     m_nurbs.Evaluate (param, 2, 2, pointAndTangents);
00222     pt (0) = pointAndTangents[0];
00223     pt (1) = pointAndTangents[1];
00224     t (0) = pointAndTangents[2];
00225     t (1) = pointAndTangents[3];
00226     n (0) = pointAndTangents[4];
00227     n (1) = pointAndTangents[5];
00228     n.normalize ();
00229 
00230     if (p < int (m_data->interior_weight.size ()))
00231       wInt = m_data->interior_weight[p];
00232 
00233     addPointConstraint (m_data->interior_param[p], m_data->interior[p], n, wInt, row);
00234   }
00235 }


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