00001 #include <iostream>
00002 #include <stdlib.h>
00003 #include <nlopt.h>
00004
00005 #include "nlopt_solver.h"
00006
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 if(algorithm == Optimization::NLopt::ISRES || algorithm == Optimization::NLopt::SLSQP)
00040 {
00041 if(algorithm == Optimization::NLopt::ISRES)
00042 {
00043 solver = nlopt_create(NLOPT_GN_ISRES, m_x);
00044 nlopt_set_maxeval(solver, 1e6);
00045 nlopt_set_maxtime(solver, 24*60*60);
00046 }
00047 else
00048 {
00049 solver = nlopt_create(NLOPT_LD_SLSQP, m_x);
00050 nlopt_set_ftol_rel(solver, ftol);
00051 nlopt_set_xtol_rel(solver, xtol);
00052
00053 }
00054 }
00055 else if(algorithm == Optimization::NLopt::G_DIRECT || algorithm == Optimization::NLopt::G_DIRECT_L || algorithm == Optimization::NLopt::CCSA)
00056 {
00057 nlopt_opt core_solver;
00058 if(algorithm == Optimization::NLopt::CCSA)
00059 {
00060 core_solver = nlopt_create(NLOPT_LD_CCSAQ, m_x);
00061 nlopt_set_ftol_rel(core_solver, ftol);
00062 nlopt_set_xtol_rel(core_solver, xtol);
00063 nlopt_set_maxeval(core_solver, 1e6);
00064 }
00065 else
00066 {
00067 if(algorithm == Optimization::NLopt::G_DIRECT)
00068 {
00069 core_solver = nlopt_create(NLOPT_GN_ORIG_DIRECT, m_x);
00070 }
00071 else
00072 {
00073 core_solver = nlopt_create(NLOPT_GN_ORIG_DIRECT_L, m_x);
00074 }
00075 nlopt_set_maxeval(core_solver, 1e6);
00076 nlopt_set_maxtime(core_solver, 24*60*60);
00077 }
00078 solver = nlopt_create(NLOPT_AUGLAG_EQ, m_x);
00079 nlopt_set_local_optimizer(solver, core_solver);
00080 nlopt_set_ftol_rel(solver, ftol);
00081 nlopt_set_xtol_rel(solver, xtol);
00082 nlopt_set_maxeval(solver, 1e6);
00083 nlopt_destroy(core_solver);
00084 }
00085 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)
00086 {
00087 nlopt_opt core_solver;
00088 if(algorithm == Optimization::NLopt::DIRECT || algorithm == Optimization::NLopt::DIRECT_L || algorithm == Optimization::NLopt::CRS || algorithm == Optimization::NLopt::STOGO)
00089 {
00090 if(algorithm == Optimization::NLopt::DIRECT)
00091 {
00092 core_solver = nlopt_create(NLOPT_GN_DIRECT, m_x);
00093 }
00094 else if(algorithm == Optimization::NLopt::DIRECT_L)
00095 {
00096 core_solver = nlopt_create(NLOPT_GN_DIRECT_L, m_x);
00097 }
00098 else if(algorithm == Optimization::NLopt::CRS)
00099 {
00100 core_solver = nlopt_create(NLOPT_GN_CRS2_LM, m_x);
00101 }
00102 else
00103 {
00104 core_solver = nlopt_create(NLOPT_GD_STOGO, m_x);
00105 }
00106 nlopt_set_maxeval(core_solver, 1e6);
00107 nlopt_set_maxtime(core_solver, 24*60*60);
00108 }
00109 else
00110 {
00111 if(algorithm == Optimization::NLopt::L_BFGS)
00112 {
00113 core_solver = nlopt_create(NLOPT_LD_LBFGS, m_x);
00114 }
00115 else if(algorithm == Optimization::NLopt::TN)
00116 {
00117 core_solver = nlopt_create(NLOPT_LD_TNEWTON_PRECOND_RESTART, m_x);
00118 }
00119 else
00120 {
00121 core_solver = nlopt_create(NLOPT_LD_VAR2, m_x);
00122 }
00123 nlopt_set_ftol_rel(core_solver, ftol);
00124 nlopt_set_xtol_rel(core_solver, xtol);
00125
00126 }
00127 solver = nlopt_create(NLOPT_AUGLAG, m_x);
00128 nlopt_set_local_optimizer(solver, core_solver);
00129 nlopt_set_ftol_rel(solver, ftol);
00130 nlopt_set_xtol_rel(solver, xtol);
00131
00132 nlopt_destroy(core_solver);
00133 } else if ( algorithm == Optimization::NLopt::COBYLA ||
00134 algorithm == Optimization::NLopt::BOBYQA ||
00135 algorithm == Optimization::NLopt::NEWUOA ||
00136 algorithm == Optimization::NLopt::PRAXIS ||
00137 algorithm == Optimization::NLopt::NelderMeadSimplex ||
00138 algorithm == Optimization::NLopt::Sbplx ){
00139 if(algorithm == Optimization::NLopt::COBYLA)
00140 {
00141 solver = nlopt_create(NLOPT_LN_COBYLA, m_x);
00142 nlopt_set_ftol_rel(solver, ftol);
00143 nlopt_set_xtol_rel(solver, xtol);
00144 }
00145 else if(algorithm == Optimization::NLopt::BOBYQA)
00146 {
00147 solver = nlopt_create(NLOPT_LN_BOBYQA, m_x);
00148 nlopt_set_ftol_rel(solver, ftol);
00149 nlopt_set_xtol_rel(solver, xtol);
00150 }
00151 else if(algorithm == Optimization::NLopt::NEWUOA)
00152 {
00153 solver = nlopt_create(NLOPT_LN_NEWUOA, m_x);
00154 nlopt_set_ftol_rel(solver, ftol);
00155 nlopt_set_xtol_rel(solver, xtol);
00156 }
00157 else if(algorithm == Optimization::NLopt::PRAXIS)
00158 {
00159 solver = nlopt_create(NLOPT_LN_PRAXIS, m_x);
00160 nlopt_set_ftol_rel(solver, ftol);
00161 nlopt_set_xtol_rel(solver, xtol);
00162 }
00163 else if(algorithm == Optimization::NLopt::NelderMeadSimplex)
00164 {
00165 solver = nlopt_create( NLOPT_LN_NELDERMEAD, m_x);
00166 nlopt_set_ftol_rel(solver, ftol);
00167 nlopt_set_xtol_rel(solver, xtol);
00168 }
00169 else if(algorithm == Optimization::NLopt::Sbplx)
00170 {
00171 solver = nlopt_create(NLOPT_LN_SBPLX, m_x);
00172 nlopt_set_ftol_rel(solver, ftol);
00173 nlopt_set_xtol_rel(solver, xtol);
00174 }
00175 }
00176
00177 if ( max_eval > 0 ) nlopt_set_maxeval(solver,max_eval) ;
00178 if ( max_time > 0 ) nlopt_set_maxtime(solver,max_time) ;
00179
00180 nlopt_set_lower_bounds(solver, x_min);
00181 nlopt_set_upper_bounds(solver, x_max);
00182
00183 nlopt_set_min_objective(solver, NLoptSolver::ObjectiveFunctionWrapper, this);
00184
00185
00186 double equality_constraint_tolerance[m_g];
00187 std::fill(equality_constraint_tolerance, equality_constraint_tolerance + m_g, eqthre);
00188 nlopt_add_equality_mconstraint(solver, m_g, NLoptSolver::EqualityConstraintWrapper, this, equality_constraint_tolerance);
00189
00190
00191 double inequality_constraint_tolerance[m_h];
00192 std::fill(inequality_constraint_tolerance, inequality_constraint_tolerance + m_h, eqthre);
00193 nlopt_add_inequality_mconstraint(solver, m_h, NLoptSolver::InequalityConstraintWrapper, this, inequality_constraint_tolerance);
00194 int major, minor, bugfix;
00195 nlopt_version(&major, &minor, &bugfix);
00196 }
00197
00198 NLoptSolver::~NLoptSolver()
00199 {
00200 nlopt_destroy(solver);
00201 }
00202
00203 double NLoptSolver::ObjectiveFunctionWrapper(unsigned int n, const double* x, double* df, void* self)
00204 {
00205
00206 NLoptSolver* self_=reinterpret_cast<NLoptSolver*>(self);
00207 my_copy((double*)x,self_->x,self_->m_x) ;
00208
00209 double f=self_->ObjectiveFunctionCost();
00210
00211
00212
00213 if(df != NULL)
00214 {
00215 my_copy(df,self_->dfbuf,1 * self_->m_x) ;
00216 self_->ObjectiveFunctionGradient(self_->dfbuf);
00217 my_copy(self_->dfbuf, df,1 * self_->m_x) ;
00218
00219
00220 }
00221 else
00222 {
00223
00224
00225 }
00226
00227 self_->iteration++;
00228 return f;
00229 }
00230
00231
00232 double NLoptSolver::ObjectiveFunctionCost()
00233 {
00234 this->n_f++;
00235
00236 if ( this->f ) (*(this->f))(this->x,this->fbuf) ;
00237 return this->fbuf[0];
00238 }
00239
00240
00241 void NLoptSolver::ObjectiveFunctionGradient(double* dfbuf)
00242 {
00243 this->n_df++;
00244
00245
00246
00247 if ( this->df ) (*(this->df))(this->x,dfbuf) ;
00248 }
00249
00250 void NLoptSolver::EqualityConstraintWrapper(unsigned int m, double* g, unsigned int n, const double* x, double* dg, void* self)
00251 {
00252
00253 NLoptSolver* self_=reinterpret_cast<NLoptSolver*>(self);
00254
00255 my_copy((double*)x,self_->x,self_->m_x) ;
00256
00257 my_copy(g,self_->gbuf,self_->m_g) ;
00258 self_->EqualityConstraintCost(self_->gbuf);
00259 my_copy(self_->gbuf,g,self_->m_g) ;
00260
00261 if(dg != NULL)
00262 {
00263 my_copy(dg,self_->dgbuf,self_->m_x * self_->m_g) ;
00264 self_->EqualityConstraintGradient(self_->dgbuf);
00265 my_copy(self_->dgbuf,dg,self_->m_x * self_->m_g) ;
00266 }
00267 }
00268
00269
00270 void NLoptSolver::EqualityConstraintCost(double* gbuf)
00271 {
00272 this->n_g++;
00273 if ( this->g ) (*(this->g))(this->x,gbuf) ;
00274
00275
00276 }
00277
00278
00279 void NLoptSolver::EqualityConstraintGradient(double* dgbuf)
00280 {
00281 this->n_dg++;
00282 if ( this->dg ) (*(this->dg))(this->x,dgbuf) ;
00283 }
00284
00285 void NLoptSolver::InequalityConstraintWrapper(unsigned int m, double* h, unsigned int n, const double* x, double* dh, void* self)
00286 {
00287
00288 NLoptSolver* self_=reinterpret_cast<NLoptSolver*>(self);
00289 my_copy((double*)x,self_->x,self_->m_x) ;
00290
00291 my_copy(h,self_->hbuf,self_->m_h) ;
00292 self_->InequalityConstraintCost(self_->hbuf);
00293 my_copy(self_->hbuf,h,self_->m_h) ;
00294
00295 if(dh != NULL)
00296 {
00297 my_copy(dh,self_->dhbuf,self_->m_x * self_->m_h) ;
00298 self_->InequalityConstraintGradient(self_->dhbuf);
00299 my_copy(self_->dhbuf,dh,self_->m_x * self_->m_h) ;
00300 }
00301
00302
00303 }
00304
00305
00306 void NLoptSolver::InequalityConstraintCost(double* hbuf)
00307 {
00308 this->n_h++;
00309 if ( this->h ) (*(this->h))(this->x,hbuf) ;
00310
00311 }
00312
00313
00314 void NLoptSolver::InequalityConstraintGradient(double* dhbuf)
00315 {
00316 this->n_dh++;
00317 if ( this->dh ) (*(this->dh))(this->x,dhbuf) ;
00318 }
00319
00320
00321 int NLoptSolver::Optimize()
00322 {
00323
00324 double cost;
00325 nlopt_result result=nlopt_optimize(this->solver, this->x, &cost);
00326
00327 return result ;
00328 }