fitting_curve_2d_apdm.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_APDM_H
00039 #define NURBS_FITTING_CURVE_2D_APDM_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   {
00055     class PCL_EXPORTS FittingCurve2dAPDM
00056     {
00057       public:
00058 
00060         struct Parameter
00061         {
00062           double interior_sigma2;
00063           double smoothness;
00064           double closest_point_weight;
00065           double closest_point_sigma2;
00066           unsigned closest_point_resolution;
00067           double smooth_concavity;
00068           double rScale;
00069           Parameter () :
00070             interior_sigma2 (0.1), smoothness (0.1), closest_point_weight (0.1), closest_point_sigma2 (0.1),
00071                 closest_point_resolution (0), smooth_concavity (1.0), rScale (1.0)
00072           {
00073           }
00074         };
00075 
00076         struct FitParameter
00077         {
00078           pcl::on_nurbs::FittingCurve2dAPDM::Parameter param;
00079           double addCPsAccuracy;        // add CPs at points where this threshold is exceeded
00080           unsigned addCPsIteration;     // add CPs at every "addCPsIteration" iteration
00081           unsigned maxCPs;              // maximum number of CPs
00082 
00083           double accuracy;              // threshold for incremental change of CPs (termination criterion)
00084           unsigned iterations;          // maximum number of fitting iterations
00085         };
00086 
00087         ON_TextLog m_out;
00088         ON_NurbsCurve m_nurbs;
00089         NurbsDataCurve2d *m_data;
00090 
00094         FittingCurve2dAPDM (int order, NurbsDataCurve2d *data);
00095 
00099         FittingCurve2dAPDM (NurbsDataCurve2d *data, const ON_NurbsCurve &nc);
00100 
00105         static int
00106         findElement (double xi, const std::vector<double> &elements);
00107 
00109         void
00110         refine ();
00111 
00114         void
00115         refine (double xi);
00116 
00119         void
00120         fitting (FitParameter &param);
00121 
00125         virtual void
00126         assemble (const Parameter &parameter);
00127 
00130         virtual double
00131         solve (double damp = 1.0);
00132 
00135         virtual double
00136         updateCurve (double damp);
00137 
00141         void
00142         addCPsOnClosestPointViolation (double max_error);
00143 
00148         static ON_NurbsCurve
00149         removeCPsOnLine (const ON_NurbsCurve &nurbs, double min_curve_th = -0.9);
00150 
00155         static ON_NurbsCurve
00156         initCPsNurbsCurve2D (int order, const vector_vec2d &cps);
00157 
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 
00169         static std::vector<double>
00170         getElementVector (const ON_NurbsCurve &nurbs);
00171 
00183         static double
00184         inverseMapping (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, const double &hint, double &error,
00185                         Eigen::Vector2d &p, Eigen::Vector2d &t, double rScale, int maxSteps = 100,
00186                         double accuracy = 1e-6, bool quiet = true);
00187 
00188         static double
00189         inverseMappingO2 (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double &error, Eigen::Vector2d &p,
00190                           Eigen::Vector2d &t);
00191 
00196         static double
00197         findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt);
00198         static double
00199         findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double hint);
00200 
00202         inline void
00203         setQuiet (bool val)
00204         {
00205           m_quiet = val;
00206           m_solver.setQuiet (val);
00207         }
00208 
00210         inline void
00211         setInverseParams (int max_steps = 200, double accuracy = 1e-6)
00212         {
00213           in_max_steps = max_steps;
00214           in_accuracy = accuracy;
00215         }
00216 
00217       protected:
00219         virtual void
00220         addPointConstraint (const double &param, const Eigen::Vector2d &point, double weight, unsigned &row);
00221 
00223         virtual void
00224         addCageRegularisation (double weight, unsigned &row, const std::vector<double> &elements, double wConcav = 0.0);
00225 
00227         virtual void
00228         assembleInterior (double wInt, double sigma2, double rScale, unsigned &row);
00229 
00232         virtual void
00233         assembleClosestPoints (const std::vector<double> &elements, double weight, double sigma2,
00234                                unsigned samples_per_element, unsigned &row);
00235 
00236         NurbsSolve m_solver;
00237         bool m_quiet;
00238         int in_max_steps;
00239         double in_accuracy;
00240     };
00241   }
00242 }
00243 
00244 #endif


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