fitting_curve_2d_pdm.h
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 #ifndef NURBS_FITTING_CURVE_2D_PDM_H
00039 #define NURBS_FITTING_CURVE_2D_PDM_H
00040 
00041 #include <pcl/pcl_exports.h>
00042 #include <pcl/surface/on_nurbs/nurbs_tools.h>
00043 #include <pcl/surface/on_nurbs/nurbs_data.h>
00044 #include <pcl/surface/on_nurbs/nurbs_solve.h>
00045 
00046 namespace pcl
00047 {
00048   namespace on_nurbs
00049   {
00050 
00056     class PCL_EXPORTS FittingCurve2dPDM
00057     {
00058       public:
00060         struct Parameter
00061         {
00062           double smoothness;
00063           double rScale;
00064           Parameter () :
00065             smoothness (0.1), rScale (1.0)
00066           {
00067           }
00068         };
00069 
00070         struct FitParameter
00071         {
00072           pcl::on_nurbs::FittingCurve2dPDM::Parameter param;
00073           unsigned refinement;
00074           double addCPsAccuracy;
00075           unsigned addCPsIteration;
00076           unsigned maxCPs;
00077 
00078           double meanDeltaCPS;
00079         };
00080 
00081         ON_TextLog m_out;
00082         ON_NurbsCurve m_nurbs;
00083         NurbsDataCurve2d *m_data;
00084 
00089         FittingCurve2dPDM (int order, NurbsDataCurve2d *data);
00090 
00095         FittingCurve2dPDM (NurbsDataCurve2d *data, const ON_NurbsCurve &nc);
00096 
00102         static int
00103         findElement (double xi, const std::vector<double> &elements);
00104 
00106         void
00107         refine ();
00108 
00112         void
00113         refine (double xi);
00114 
00119         virtual void
00120         assemble (const Parameter &parameter);
00121 
00125         virtual double
00126         solve (double damp = 1.0);
00127 
00131         virtual double
00132         updateCurve (double damp);
00133 
00138         void
00139         addCPsOnClosestPointViolation (double max_error);
00140 
00146         static ON_NurbsCurve
00147         removeCPsOnLine (const ON_NurbsCurve &nurbs, double min_curve_th = -0.9);
00148 
00154         static ON_NurbsCurve
00155         initCPsNurbsCurve2D (int order, const vector_vec2d &cps);
00156 
00164         static ON_NurbsCurve
00165         initNurbsCurve2D (int order, const vector_vec2d &data, int ncps = 0, double radiusF = 1.0);
00166         //  static ON_NurbsCurve initNurbsCurvePCA(int order, const vector_vec2d &data);
00167 
00171         static void
00172         reverse(ON_NurbsCurve &curve);
00173 
00175         static std::vector<double>
00176         getElementVector (const ON_NurbsCurve &nurbs);
00177 
00190         static double
00191         inverseMapping (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, const double &hint, double &error,
00192                         Eigen::Vector2d &p, Eigen::Vector2d &t, double rScale, int maxSteps = 100,
00193                         double accuracy = 1e-6, bool quiet = true);
00194 
00195         static double
00196         inverseMappingO2 (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double &error, Eigen::Vector2d &p,
00197                           Eigen::Vector2d &t);
00198 
00204         static double
00205         findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt);
00206         static double
00207         findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double hint);
00208 
00210         inline void
00211         setQuiet (bool val)
00212         {
00213           m_quiet = val;
00214           m_solver.setQuiet (val);
00215         }
00216 
00218         inline void
00219         setInverseParams (int max_steps = 200, double accuracy = 1e-6)
00220         {
00221           in_max_steps = max_steps;
00222           in_accuracy = accuracy;
00223         }
00224 
00225       protected:
00227         virtual void
00228         addPointConstraint (const double &param, const Eigen::Vector2d &point, double weight, unsigned &row);
00229 
00231         virtual void
00232         addCageRegularisation (double weight, unsigned &row);
00233 
00235         virtual void
00236         assembleInterior (double wInt, double rScale, unsigned &row);
00237 
00238         NurbsSolve m_solver;
00239         bool m_quiet;
00240         int in_max_steps;
00241         double in_accuracy;
00242 
00243     };
00244   }
00245 }
00246 
00247 #endif


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