global_optimization_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_OPTIMIZATION_H
00039 #define NURBS_OPTIMIZATION_H
00040 
00041 #include <pcl/surface/on_nurbs/nurbs_tools.h>
00042 #include <pcl/surface/on_nurbs/nurbs_data.h>
00043 #include <pcl/surface/on_nurbs/nurbs_solve.h>
00044 
00045 namespace pcl
00046 {
00047   namespace on_nurbs
00048   {
00049 
00055     class GlobalOptimization
00056     {
00057     public:
00058 
00060       struct Parameter
00061       {
00062         double interior_weight;
00063         double interior_smoothness;
00064 
00065         double boundary_weight;
00066         double boundary_smoothness;
00067 
00068         double closing_weight;
00069         double closing_sigma;
00070         unsigned closing_samples;
00071 
00072         double common_weight;
00073 
00074         Parameter (double intW = 1.0, double intS = 1e-6, double bndW = 0.0, double bndS = 1e-6, double cloW = 0.0,
00075                    double cloSig = 0.0, unsigned cloSam = 0, double comW = 0.0) :
00076           interior_weight (intW), interior_smoothness (intS), boundary_weight (bndW), boundary_smoothness (bndS),
00077               closing_weight (cloW), closing_sigma (cloSig), closing_samples (cloSam), common_weight (comW)
00078         {
00079         }
00080       };
00081 
00085       GlobalOptimization (const std::vector<NurbsDataSurface*> &data, const std::vector<ON_NurbsSurface*> &nurbs);
00086 
00090       void
00091       setCommonBoundary (const vector_vec3d &boundary, const vector_vec2i &nurbs_indices);
00092 
00096       virtual void
00097       assemble (Parameter params = Parameter ());
00098 
00101       virtual void
00102       solve (double damp = 1.0);
00103 
00106       virtual void
00107       updateSurf (double damp);
00108 
00112       void
00113       setInvMapParams (double im_max_steps, double im_accuracy);
00114 
00118       void
00119       refine (unsigned id, int dim);
00120 
00121       inline void
00122       setQuiet (bool val)
00123       {
00124         m_quiet = val;
00125         m_solver.setQuiet (val);
00126       }
00127 
00128     protected:
00129 
00130       std::vector<NurbsDataSurface*> m_data;
00131       std::vector<ON_NurbsSurface*> m_nurbs;
00132 
00133       void
00134       assembleCommonParams (unsigned id1, double weight, unsigned &row);
00135 
00137       virtual void
00138       assembleCommonBoundaries (unsigned id1, double weight, unsigned &row);
00139 
00141       virtual void
00142       assembleClosingBoundaries (unsigned id, unsigned samples, double sigma, double weight, unsigned &row);
00143 
00145       virtual void
00146       assembleInteriorPoints (unsigned id, int ncps, double weight, unsigned &row);
00147 
00149       virtual void
00150       assembleBoundaryPoints (unsigned id, int ncps, double weight, unsigned &row);
00151 
00153       virtual void
00154       assembleRegularisation (unsigned id, int ncps, double wCageRegInt, double wCageRegBnd, unsigned &row);
00155 
00157       virtual void
00158       addParamConstraint (const Eigen::Vector2i &id, const Eigen::Vector2d &params1, const Eigen::Vector2d &params2,
00159                           double weight, unsigned &row);
00160 
00162       virtual void
00163       addPointConstraint (unsigned id, int ncps, const Eigen::Vector2d &params, const Eigen::Vector3d &point,
00164                           double weight, unsigned &row);
00165 
00167       virtual void
00168       addCageInteriorRegularisation (unsigned id, int ncps, double weight, unsigned &row);
00169 
00171       virtual void
00172       addCageBoundaryRegularisation (unsigned id, int ncps, double weight, int side, unsigned &row);
00173 
00175       virtual void
00176       addCageCornerRegularisation (unsigned id, int ncps, double weight, unsigned &row);
00177 
00178     protected:
00179       NurbsSolve m_solver;
00180       bool m_quiet;
00181       unsigned m_ncols, m_nrows;
00182       int im_max_steps;
00183       double im_accuracy;
00184 
00185       // index routines
00186       int
00187       grc2gl (const ON_NurbsSurface &nurbs, int I, int J)
00188       {
00189         return nurbs.CVCount (1) * I + J;
00190       } // global row/col index to global lexicographic index
00191       int
00192       lrc2gl (const ON_NurbsSurface &nurbs, int E, int F, int i, int j)
00193       {
00194         return grc2gl (nurbs, E + i, F + j);
00195       } // local row/col index to global lexicographic index
00196       int
00197       gl2gr (const ON_NurbsSurface &nurbs, int A)
00198       {
00199         return (static_cast<int> (A / nurbs.CVCount (1)));
00200       } // global lexicographic in global row index
00201       int
00202       gl2gc (const ON_NurbsSurface &nurbs, int A)
00203       {
00204         return (static_cast<int> (A % nurbs.CVCount (1)));
00205       } // global lexicographic in global col index
00206     };
00207 
00208   }
00209 }
00210 #endif
00211 


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