fitting_curve_2d.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_H
00039 #define NURBS_FITTING_CURVE_2D_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 FittingCurve2d
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::FittingCurve2d::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         FittingCurve2d (int order, NurbsDataCurve2d *data);
00090 
00095         FittingCurve2d (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 
00122         virtual void
00123         addControlPointConstraint (int i, const Eigen::Vector2d &f, double weight);
00124 
00128         virtual double
00129         solve (double damp = 1.0);
00130 
00134         virtual double
00135         updateCurve (double damp);
00136 
00142         static ON_NurbsCurve
00143         initNurbsCPS (int order, const vector_vec2d &cps);
00144 
00151         static ON_NurbsCurve
00152         initNurbsPCA (int order, NurbsDataCurve2d *data, int ncps=0);
00153 
00157         static void
00158         reverse(ON_NurbsCurve &curve);
00159 
00161         static std::vector<double>
00162         getElementVector (const ON_NurbsCurve &nurbs);
00163 
00176         static double
00177         inverseMapping (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, const double &hint, double &error,
00178                         Eigen::Vector2d &p, Eigen::Vector2d &t, double rScale, int maxSteps = 100,
00179                         double accuracy = 1e-6, bool quiet = true);
00180 
00181         static double
00182         inverseMappingO2 (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double &error, Eigen::Vector2d &p,
00183                           Eigen::Vector2d &t);
00184 
00190         static double
00191         findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt);
00192         static double
00193         findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double hint);
00194 
00196         inline void
00197         setQuiet (bool val)
00198         {
00199           m_quiet = val;
00200           m_solver.setQuiet (val);
00201         }
00202 
00204         inline void
00205         setInverseParams (int max_steps = 200, double accuracy = 1e-6)
00206         {
00207           in_max_steps = max_steps;
00208           in_accuracy = accuracy;
00209         }
00210 
00211       protected:
00213         virtual void
00214         addPointConstraint (const double &param, const Eigen::Vector2d &point, double weight, unsigned &row);
00215 
00217         virtual void
00218         addCageRegularisation (double weight, unsigned &row);
00219 
00221         virtual void
00222         assembleInterior (double wInt, double rScale, unsigned &row);
00223 
00224         NurbsSolve m_solver;
00225         bool m_quiet;
00226         int in_max_steps;
00227         double in_accuracy;
00228 
00229     };
00230   }
00231 }
00232 
00233 #endif


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