fitting_surface_tdm.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_PATCH_TDM_H
00039 #define NURBS_FITTING_PATCH_TDM_H
00040 
00041 #include <pcl/surface/on_nurbs/fitting_surface_pdm.h>
00042 
00043 namespace pcl
00044 {
00045   namespace on_nurbs
00046   {
00051     class FittingSurfaceTDM : public FittingSurface
00052     {
00053     public:
00054 
00056       struct ParameterTDM : public FittingSurface::Parameter
00057       {
00058         double interior_tangent_weight;
00059         double boundary_tangent_weight;
00060 
00061         ParameterTDM (double intW = 1.0, double intS = 0.000001, double intR = 0.0, double intTW = 0.1,
00062                       double bndW = 1.0, double bndS = 0.000001, double bndR = 0.0, double bndTW = 0.1,
00063                       unsigned regU = 0, unsigned regV = 0) :
00064           Parameter (intW, intS, intR, bndW, bndS, bndR, regU, regV), interior_tangent_weight (intTW),
00065               boundary_tangent_weight (bndTW)
00066         {
00067         }
00068       };
00069 
00073       FittingSurfaceTDM (NurbsDataSurface *data, const ON_NurbsSurface &ns);
00074 
00079       FittingSurfaceTDM (int order, NurbsDataSurface *data, Eigen::Vector3d z = Eigen::Vector3d (0.0, 0.0, 1.0));
00080 
00084       virtual void
00085       assemble (ParameterTDM param = ParameterTDM ());
00086 
00089       virtual void
00090       solve (double damp = 1.0);
00091 
00094       virtual void
00095       updateSurf (double damp);
00096 
00097     protected:
00098 
00100       virtual void
00101       assembleInterior (double wInt, double wTangent, unsigned &row);
00102 
00104       virtual void
00105       assembleBoundary (double wBnd, double wTangent, unsigned &row);
00106 
00108       virtual void
00109       addPointConstraint (const Eigen::Vector2d &params, const Eigen::Vector3d &point, const Eigen::Vector3d &normal,
00110                           const Eigen::Vector3d &tu, const Eigen::Vector3d &tv, double tangent_weight, double weight,
00111                           unsigned &row);
00112 
00114       virtual void
00115       addCageInteriorRegularisation (double weight, unsigned &row);
00116 
00118       virtual void
00119       addCageBoundaryRegularisation (double weight, int side, unsigned &row);
00120 
00122       virtual void
00123       addCageCornerRegularisation (double weight, unsigned &row);
00124 
00125       virtual void
00126       addInteriorRegularisation (int, int, int, double, unsigned &)
00127       {
00128       }
00129       virtual void
00130       addBoundaryRegularisation (int, int, int, double, unsigned &)
00131       {
00132       }
00133     };
00134 
00135   }
00136 }
00137 
00138 #endif /* NURBS_FITTING_PATCH_TDM_H */


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