nlopt_solver.cpp
Go to the documentation of this file.
00001 #include <iostream>
00002 #include <stdlib.h>
00003 #include <nlopt.h>
00004 
00005 #include "nlopt_solver.h"
00006 //#include "eus_function.cpp"
00007 
00008 NLoptSolver::NLoptSolver(double* x,
00009                 const double* x_min,
00010                 const double* x_max,
00011                 int (*f)(double*,double*), int (*df)(double*,double*),
00012                 int (*g)(double*,double*), int (*dg)(double*,double*),
00013                 int (*h)(double*,double*), int (*dh)(double*,double*),
00014                 int m_x, int m_g, int m_h,
00015                 double ftol, double xtol, double eqthre, int max_eval, double max_time,
00016                 Optimization::NLopt::Algorithm algorithm)
00017         :
00018                 x(x), m_x(m_x), m_g(m_g), m_h(m_h), iteration(0), n_f(0), n_df(0), n_g(0), n_dg(0), n_h(0), n_dh(0) {
00019         this->f = f ;
00020         this->df = df;
00021         this->g = g ;
00022         this->dg = dg;
00023         this->h = h ;
00024         this->dh = dh;
00025         //
00026         this->fbuf = (double*)malloc(sizeof(double)*1) ;
00027         this->fbuf[0] = 0 ;
00028         this->dfbuf = (double*)malloc(sizeof(double)*1*m_x) ;
00029         for ( uint i=0 ; i<1*m_x ; i++ ) this->dfbuf[i] = 0 ;
00030         this->gbuf = (double*)malloc(sizeof(double)*m_g) ;
00031         for ( uint i=0 ; i<m_g ; i++ ) this->gbuf[i] = 0 ;
00032         this->dgbuf = (double*)malloc(sizeof(double)*m_g*m_x) ;
00033         for ( uint i=0 ; i<m_x*m_g ; i++ ) this->dgbuf[i] = 0 ;
00034         this->hbuf = (double*)malloc(sizeof(double)*m_h) ;
00035         for ( uint i=0 ; i<m_h ; i++ ) this->hbuf[i] = 0 ;
00036         this->dhbuf = (double*)malloc(sizeof(double)*m_h*m_x) ;
00037         for ( uint i=0 ; i<m_x*m_h ; i++ ) this->dhbuf[i] = 0 ;
00038         //
00039         // ラグランジュ法を用いて全てのアルゴリズムで制約条件を扱えるようにする
00040         if(algorithm == Optimization::NLopt::ISRES || algorithm == Optimization::NLopt::SLSQP)
00041         {
00042           core_solver = nlopt_create(NLOPT_LD_CCSAQ, m_x); // dummy
00043                 if(algorithm == Optimization::NLopt::ISRES)
00044                 {
00045                         solver = nlopt_create(NLOPT_GN_ISRES, m_x);
00046                         nlopt_set_maxeval(solver, 1e6);
00047                         nlopt_set_maxtime(solver, 24*60*60);
00048                 }
00049                 else
00050                 {
00051                         solver = nlopt_create(NLOPT_LD_SLSQP, m_x);
00052                         nlopt_set_ftol_rel(solver, ftol);
00053                         nlopt_set_xtol_rel(solver, xtol);
00054                         //nlopt_set_maxeval(solver, 1e3);
00055                 }
00056         }
00057         else if(algorithm == Optimization::NLopt::G_DIRECT || algorithm == Optimization::NLopt::G_DIRECT_L || algorithm == Optimization::NLopt::CCSA)
00058         {
00059           // nlopt_opt core_solver;
00060                 if(algorithm == Optimization::NLopt::CCSA)
00061                 {
00062                         core_solver = nlopt_create(NLOPT_LD_CCSAQ, m_x);
00063                         nlopt_set_ftol_rel(core_solver, ftol);
00064                         nlopt_set_xtol_rel(core_solver, xtol);
00065                         nlopt_set_maxeval(core_solver, 1e6);
00066                 }
00067                 else
00068                 {
00069                         if(algorithm == Optimization::NLopt::G_DIRECT)
00070                         {
00071                                 core_solver = nlopt_create(NLOPT_GN_ORIG_DIRECT, m_x);
00072                         }
00073                         else
00074                         {
00075                                 core_solver = nlopt_create(NLOPT_GN_ORIG_DIRECT_L, m_x);
00076                         }
00077                         nlopt_set_maxeval(core_solver, 1e6);
00078                         nlopt_set_maxtime(core_solver, 24*60*60);
00079                         nlopt_set_ftol_rel(core_solver, ftol);
00080                         nlopt_set_xtol_rel(core_solver, xtol);
00081                 }
00082                 solver = nlopt_create(NLOPT_AUGLAG_EQ, m_x);
00083                 nlopt_set_local_optimizer(solver, core_solver);
00084                 nlopt_set_ftol_rel(solver, ftol);
00085                 nlopt_set_xtol_rel(solver, xtol);
00086                 nlopt_set_maxeval(solver, 1e6);
00087                 // nlopt_destroy(core_solver);
00088         }
00089         else if(algorithm == Optimization::NLopt::DIRECT || algorithm == Optimization::NLopt::DIRECT_L || algorithm == Optimization::NLopt::CRS || algorithm == Optimization::NLopt::STOGO || algorithm == Optimization::NLopt::L_BFGS || algorithm == Optimization::NLopt::TN || algorithm == Optimization::NLopt::SL_VM)
00090         {
00091           // nlopt_opt core_solver;
00092                 if(algorithm == Optimization::NLopt::DIRECT || algorithm == Optimization::NLopt::DIRECT_L || algorithm == Optimization::NLopt::CRS || algorithm == Optimization::NLopt::STOGO)
00093                 {
00094                         if(algorithm == Optimization::NLopt::DIRECT)
00095                         {
00096                                 core_solver = nlopt_create(NLOPT_GN_DIRECT, m_x);
00097                         }
00098                         else if(algorithm == Optimization::NLopt::DIRECT_L)
00099                         {
00100                                 core_solver = nlopt_create(NLOPT_GN_DIRECT_L, m_x);
00101                         }
00102                         else if(algorithm == Optimization::NLopt::CRS)
00103                         {
00104                                 core_solver = nlopt_create(NLOPT_GN_CRS2_LM, m_x);
00105                         }
00106                         else
00107                         {
00108                                 core_solver = nlopt_create(NLOPT_GD_STOGO, m_x);
00109                         }
00110                         nlopt_set_maxeval(core_solver, 1e6);
00111                         nlopt_set_maxtime(core_solver, 24*60*60);
00112                         nlopt_set_ftol_rel(core_solver, ftol);
00113                         nlopt_set_xtol_rel(core_solver, xtol);
00114                 }
00115                 else
00116                 {
00117                         if(algorithm == Optimization::NLopt::L_BFGS)
00118                         {
00119                                 core_solver = nlopt_create(NLOPT_LD_LBFGS, m_x);
00120                         }
00121                         else if(algorithm == Optimization::NLopt::TN)
00122                         {
00123                                 core_solver = nlopt_create(NLOPT_LD_TNEWTON_PRECOND_RESTART, m_x);
00124                         }
00125                         else
00126                         {
00127                                 core_solver = nlopt_create(NLOPT_LD_VAR2, m_x);
00128                         }
00129                         nlopt_set_ftol_rel(core_solver, ftol);
00130                         nlopt_set_xtol_rel(core_solver, xtol);
00131                         //nlopt_set_maxeval(core_solver, 1e3);
00132                 }
00133                 solver = nlopt_create(NLOPT_AUGLAG, m_x);
00134                 nlopt_set_local_optimizer(solver, core_solver);
00135                 nlopt_set_ftol_rel(solver, ftol);
00136                 nlopt_set_xtol_rel(solver, xtol);
00137                 //nlopt_set_maxeval(solver, 1e3);
00138                 //              nlopt_destroy(core_solver);
00139         } else if ( algorithm == Optimization::NLopt::COBYLA ||
00140                         algorithm == Optimization::NLopt::BOBYQA ||
00141                         algorithm == Optimization::NLopt::NEWUOA ||
00142                         algorithm == Optimization::NLopt::PRAXIS ||
00143                         algorithm == Optimization::NLopt::NelderMeadSimplex ||
00144                         algorithm == Optimization::NLopt::Sbplx ){
00145           core_solver = nlopt_create(NLOPT_LD_CCSAQ, m_x); // dummy
00146                 if(algorithm == Optimization::NLopt::COBYLA)
00147                 {
00148                         solver = nlopt_create(NLOPT_LN_COBYLA, m_x);
00149                         nlopt_set_ftol_rel(solver, ftol);
00150                         nlopt_set_xtol_rel(solver, xtol);
00151                 }
00152                 else if(algorithm == Optimization::NLopt::BOBYQA)
00153                 {
00154                         solver = nlopt_create(NLOPT_LN_BOBYQA, m_x);
00155                         nlopt_set_ftol_rel(solver, ftol);
00156                         nlopt_set_xtol_rel(solver, xtol);
00157                 }
00158                 else if(algorithm == Optimization::NLopt::NEWUOA)
00159                 {
00160                         solver = nlopt_create(NLOPT_LN_NEWUOA, m_x);
00161                         nlopt_set_ftol_rel(solver, ftol);
00162                         nlopt_set_xtol_rel(solver, xtol);
00163                 }
00164                 else if(algorithm == Optimization::NLopt::PRAXIS)
00165                 {
00166                         solver = nlopt_create(NLOPT_LN_PRAXIS, m_x);
00167                         nlopt_set_ftol_rel(solver, ftol);
00168                         nlopt_set_xtol_rel(solver, xtol);
00169                 }
00170                 else if(algorithm == Optimization::NLopt::NelderMeadSimplex)
00171                 {
00172                         solver = nlopt_create( NLOPT_LN_NELDERMEAD, m_x);
00173                         nlopt_set_ftol_rel(solver, ftol);
00174                         nlopt_set_xtol_rel(solver, xtol);
00175                 }
00176                 else if(algorithm == Optimization::NLopt::Sbplx)
00177                 {
00178                         solver = nlopt_create(NLOPT_LN_SBPLX, m_x);
00179                         nlopt_set_ftol_rel(solver, ftol);
00180                         nlopt_set_xtol_rel(solver, xtol);
00181                 }
00182         }
00183         //
00184         if ( max_eval > 0 ) nlopt_set_maxeval(solver,max_eval) ;
00185         if ( max_time > 0 ) nlopt_set_maxtime(solver,max_time) ;
00186         // 定義域の設定
00187         nlopt_set_lower_bounds(solver, x_min);
00188         nlopt_set_upper_bounds(solver, x_max);
00189         // 評価関数の設定
00190         nlopt_set_min_objective(solver, NLoptSolver::ObjectiveFunctionWrapper, this);
00191         // 等式制約条件の設定
00192         // 数値的安定性のためにある程度の誤差を許容する
00193         double equality_constraint_tolerance[m_g];
00194         std::fill(equality_constraint_tolerance, equality_constraint_tolerance + m_g, eqthre);
00195         nlopt_add_equality_mconstraint(solver, m_g, NLoptSolver::EqualityConstraintWrapper, this, equality_constraint_tolerance);
00196         // 不等式制約条件の設定
00197         // 数値的安定性のためにある程度の誤差を許容する
00198         double inequality_constraint_tolerance[m_h];
00199         std::fill(inequality_constraint_tolerance, inequality_constraint_tolerance + m_h, eqthre);
00200         nlopt_add_inequality_mconstraint(solver, m_h, NLoptSolver::InequalityConstraintWrapper, this, inequality_constraint_tolerance);
00201         int major, minor, bugfix;
00202         nlopt_version(&major, &minor, &bugfix);
00203 }
00204 
00205 NLoptSolver::~NLoptSolver()
00206 {
00207         nlopt_destroy(solver);
00208         if ( core_solver ) {
00209           nlopt_destroy(core_solver);
00210           core_solver = NULL;
00211         }
00212 }
00213 
00214 double NLoptSolver::ObjectiveFunctionWrapper(unsigned int n, const double* x, double* df, void* self)
00215 {
00216         // 変数に代入する
00217         NLoptSolver* self_=reinterpret_cast<NLoptSolver*>(self);
00218         my_copy((double*)x,self_->x,self_->m_x) ; //self_->x = (double*)x ;
00219         // 評価関数の計算
00220         double f=self_->ObjectiveFunctionCost();
00221         // 各イテレーションの結果を出力する
00222 //      OutputLog(self_->log_file, self_->frequency, std::setw(6) << std::right << self_->iteration << " " << std::scientific << std::setw(13) << f);
00223         // 勾配ベクトルの計算
00224         if(df != NULL)
00225         {
00226                 my_copy(df,self_->dfbuf,1 * self_->m_x) ;
00227                 self_->ObjectiveFunctionGradient(self_->dfbuf);
00228                 my_copy(self_->dfbuf, df,1 * self_->m_x) ;
00229                 // 勾配ベクトルのノルムを出力する
00230 //              OutputIterationLog(self_->log_file, self_->frequency, std::setw(13) << df_.norm());
00231         }
00232         else
00233         {
00234                 // 勾配ベクトルがない時は-を出力する
00235 //              OutputIterationLog(self_->log_file, self_->frequency, "      -      ");
00236         }
00237         // イテレーション数のカウント
00238         self_->iteration++;
00239         return f;
00240 }
00241 
00242 // 評価関数
00243 double NLoptSolver::ObjectiveFunctionCost()
00244 {
00245         this->n_f++;
00246         // 評価関数の和
00247         if ( this->f ) (*(this->f))(this->x,this->fbuf) ;
00248         return this->fbuf[0];
00249 }
00250 
00251 // 評価関数の勾配
00252 void NLoptSolver::ObjectiveFunctionGradient(double* dfbuf)
00253 {
00254         this->n_df++;
00255         // 評価関数の和の勾配ベクトル
00256 
00257 //      dfbuf[0] = 0 ;
00258         if ( this->df ) (*(this->df))(this->x,dfbuf) ;
00259 }
00260 
00261 void NLoptSolver::EqualityConstraintWrapper(unsigned int m, double* g, unsigned int n, const double* x, double* dg, void* self)
00262 {
00263         // 変数に代入する
00264         NLoptSolver* self_=reinterpret_cast<NLoptSolver*>(self);
00265 
00266         my_copy((double*)x,self_->x,self_->m_x) ; //self_->x = (double*)x ;
00267         // 不等式制約条件
00268         my_copy(g,self_->gbuf,self_->m_g) ;
00269         self_->EqualityConstraintCost(self_->gbuf);
00270         my_copy(self_->gbuf,g,self_->m_g) ;
00271         // 勾配計算
00272         if(dg != NULL)
00273         {
00274                 my_copy(dg,self_->dgbuf,self_->m_x * self_->m_g) ;
00275                 self_->EqualityConstraintGradient(self_->dgbuf);
00276                 my_copy(self_->dgbuf,dg,self_->m_x * self_->m_g) ;
00277         }
00278 }
00279 
00280 // 等式制約条件
00281 void NLoptSolver::EqualityConstraintCost(double* gbuf)
00282 {
00283         this->n_g++;
00284         if ( this->g && this->m_g>0 ) (*(this->g))(this->x,gbuf) ;
00285         //this->gbuf = gbuf ;
00286         // 等式制約条件を縦に並べる
00287 }
00288 
00289 // 等式制約条件の勾配
00290 void NLoptSolver::EqualityConstraintGradient(double* dgbuf)
00291 {
00292         this->n_dg++;
00293         if ( this->dg && this->m_g>0 ) (*(this->dg))(this->x,dgbuf) ;
00294 }
00295 
00296 void NLoptSolver::InequalityConstraintWrapper(unsigned int m, double* h, unsigned int n, const double* x, double* dh, void* self)
00297 {
00298         // 変数に代入する
00299         NLoptSolver* self_=reinterpret_cast<NLoptSolver*>(self);
00300         my_copy((double*)x,self_->x,self_->m_x) ; //self_->x = (double*)x ;
00301         // 不等式制約条件
00302         my_copy(h,self_->hbuf,self_->m_h) ;
00303         self_->InequalityConstraintCost(self_->hbuf);
00304         my_copy(self_->hbuf,h,self_->m_h) ;
00305         // 勾配行列計算
00306         if(dh != NULL)
00307         {
00308                 my_copy(dh,self_->dhbuf,self_->m_x * self_->m_h) ;
00309                 self_->InequalityConstraintGradient(self_->dhbuf);
00310                 my_copy(self_->dhbuf,dh,self_->m_x * self_->m_h) ;
00311         }
00312         // 各イテレーションの結果を出力する
00313         //OutputIterationLog(self_->log_file, self_->frequency, std::setw(14) << h_.maxCoeff() << std::fixed << std::endl);
00314 }
00315 
00316 // 不等式制約条件
00317 void NLoptSolver::InequalityConstraintCost(double* hbuf)
00318 {
00319         this->n_h++;
00320         if ( this->h && this->m_h>0 ) (*(this->h))(this->x,hbuf) ;
00321         //this->hbuf = hbuf ;
00322 }
00323 
00324 // 不等式制約条件の勾配
00325 void NLoptSolver::InequalityConstraintGradient(double* dhbuf)
00326 {
00327         this->n_dh++;
00328         if ( this->dh && this->m_h>0) (*(this->dh))(this->x,dhbuf) ;
00329 }
00330 
00331 // 最適化計算
00332 int NLoptSolver::Optimize()
00333 {
00334         // 最適化計算
00335         double cost;
00336         nlopt_result result=nlopt_optimize(this->solver, this->x, &cost);
00337         //this->output_result(result) ;
00338         this->fbuf[0] = cost;
00339         return result ;
00340 }


eus_nlopt
Author(s):
autogenerated on Wed Jul 19 2017 02:54:15