global_optimization_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_OPTIMIZATION_TDM_H
00039 #define NURBS_OPTIMIZATION_TDM_H
00040 
00041 #include <pcl/surface/on_nurbs/global_optimization_pdm.h>
00042 
00043 namespace pcl
00044 {
00045   namespace on_nurbs
00046   {
00047 
00053     class GlobalOptimizationTDM : public GlobalOptimization
00054     {
00055     public:
00056 
00058       struct ParameterTDM : public GlobalOptimization::Parameter
00059       {
00060         double interior_tangent_weight;
00061         double boundary_tangent_weight;
00062         double closing_tangent_weight;
00063 
00064         ParameterTDM (double intW = 1.0, double intS = 1e-6, double intTW = 0.01, double bndW = 0.0,
00065                       double bndS = 1e-6, double bndTW = 0.01, double cloW = 0.0, double cloSi = 0.0,
00066                       unsigned cloSa = 0, double cloTW = 0.0, double comW = 0.0) :
00067           Parameter (intW, intS, bndW, bndS, cloW, cloSi, cloSa, comW), interior_tangent_weight (intTW),
00068               boundary_tangent_weight (bndTW), closing_tangent_weight (cloTW)
00069         {
00070         }
00071         ParameterTDM (GlobalOptimization::Parameter params, double intTW = 0.01, double bndTW = 0.0, double cloTW = 0.0) :
00072           Parameter (params), interior_tangent_weight (intTW), boundary_tangent_weight (bndTW),
00073               closing_tangent_weight (cloTW)
00074         {
00075         }
00076       };
00077 
00078     public:
00079 
00083       GlobalOptimizationTDM (const std::vector<NurbsDataSurface*> &data, const std::vector<ON_NurbsSurface*> &nurbs);
00084 
00088       virtual void
00089       assemble (Parameter params);
00090 
00094       void
00095       assemble (ParameterTDM params = ParameterTDM ());
00096 
00099       virtual void
00100       solve (double damp = 1.0);
00101 
00104       virtual void
00105       updateSurf (double damp);
00106 
00107     private:
00108 
00109       virtual void
00110       assembleCommonParams (unsigned id1, double weight, unsigned &row);
00111 
00113       virtual void
00114       assembleCommonBoundaries (unsigned id1, double weight, unsigned &row);
00115 
00118       void
00119       assembleCommonBoundariesTD (unsigned id1, double wTangent, double weight, unsigned &row);
00120 
00123       virtual void
00124       assembleClosingBoundaries (unsigned id, unsigned samples, double sigma, double weight, unsigned &row);
00125 
00128       void
00129       assembleClosingBoundariesTD (unsigned id, unsigned samples, double sigma, double wTangent, double weight,
00130                                    unsigned &row);
00131 
00133       virtual void
00134       assembleInteriorPoints (unsigned id, int ncps, double weight, unsigned &row);
00135 
00137       void
00138       assembleInteriorPointsTD (unsigned id, int ncps, double wTangent, double weight, unsigned &row);
00139 
00141       virtual void
00142       assembleBoundaryPoints (unsigned id, int ncps, double weight, unsigned &row);
00143 
00145       virtual void
00146       assembleRegularisation (unsigned id, int ncps, double wCageRegInt, double wCageRegBnd, unsigned &row);
00147 
00149       virtual void
00150       addParamConstraint (const Eigen::Vector2i &id, const Eigen::Vector2d &params1, const Eigen::Vector2d &params2,
00151                           double weight, unsigned &row);
00152 
00155       virtual void
00156       addParamConstraintTD (const Eigen::Vector2i &id, const Eigen::Vector2d &params1, const Eigen::Vector2d &params2,
00157                             const Eigen::Vector3d &n, const Eigen::Vector3d &tu, const Eigen::Vector3d &tv,
00158                             double tangent_weight, double weight, unsigned &row);
00159 
00161       virtual void
00162       addPointConstraint (unsigned id, int ncps, const Eigen::Vector2d &params, const Eigen::Vector3d &point,
00163                           double weight, unsigned &row);
00164 
00166       void
00167       addPointConstraintTD (unsigned id, int ncps, const Eigen::Vector2d &params, const Eigen::Vector3d &p,
00168                             const Eigen::Vector3d &n, const Eigen::Vector3d &tu, const Eigen::Vector3d &tv,
00169                             double tangent_weight, double weight, unsigned &row);
00170 
00172       virtual void
00173       addCageInteriorRegularisation (unsigned id, int ncps, double weight, unsigned &row);
00174 
00176       virtual void
00177       addCageBoundaryRegularisation (unsigned id, int ncps, double weight, int side, unsigned &row);
00178 
00180       virtual void
00181       addCageCornerRegularisation (unsigned id, int ncps, double weight, unsigned &row);
00182 
00183     };
00184 
00185   }
00186 }
00187 #endif
00188 


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