00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #include <ifopt_snopt/snopt76_adapter.h>
00028
00029 namespace ifopt {
00030
00031 SnoptAdapter::NLPPtr SnoptAdapter::nlp_;
00032
00033 void
00034 SnoptAdapter::Solve (Problem& ref)
00035 {
00036 SnoptAdapter snopt(ref);
00037 snopt.Init();
00038 SetOptions(snopt);
00039
00040
00041 int Cold = 0;
00042
00043
00044 int nS = 0;
00045 int nInf;
00046 double sInf;
00047
00048 int INFO = snopt.solve(Cold, snopt.neF, snopt.n, snopt.ObjAdd,
00049 snopt.ObjRow, &SnoptAdapter::ObjectiveAndConstraintFct,
00050 snopt.iAfun, snopt.jAvar, snopt.A, snopt.neA,
00051 snopt.iGfun, snopt.jGvar, snopt.neG,
00052 snopt.xlow, snopt.xupp, snopt.Flow, snopt.Fupp,
00053 snopt.x, snopt.xstate, snopt.xmul,
00054 snopt.F, snopt.Fstate, snopt.Fmul,
00055 nS, nInf, sInf);
00056
00057 int EXIT = INFO - INFO%10;
00058
00059 if (EXIT != 0) {
00060 std::string msg = "Snopt failed to find a solution. EXIT:" + std::to_string(EXIT) + ", INFO:" + std::to_string(INFO);
00061 throw std::runtime_error(msg);
00062 }
00063
00064 snopt.SetVariables();
00065 }
00066
00067 void SnoptAdapter::SetOptions(SnoptAdapter& solver)
00068 {
00069
00070
00071
00072 solver.setProbName( "snopt" );
00073 solver.setIntParameter( "Major Print level", 1 );
00074 solver.setIntParameter( "Minor Print level", 1 );
00075 solver.setParameter( "Solution");
00076 solver.setIntParameter( "Derivative option", 1 );
00077 solver.setIntParameter( "Verify level ", 3 );
00078 solver.setIntParameter("Iterations limit", 200000);
00079 solver.setRealParameter( "Major feasibility tolerance", 1.0e-3);
00080 solver.setRealParameter( "Minor feasibility tolerance", 1.0e-3);
00081 solver.setRealParameter( "Major optimality tolerance", 1.0e-2);
00082 }
00083
00084 SnoptAdapter::SnoptAdapter (Problem& ref)
00085 {
00086 nlp_ = &ref;
00087 }
00088
00089 void
00090 SnoptAdapter::Init ()
00091 {
00092 int obj_count = nlp_->HasCostTerms()? 1 : 0;
00093 n = nlp_->GetNumberOfOptimizationVariables();
00094 neF = nlp_->GetNumberOfConstraints() + obj_count;
00095
00096 x = new double[n];
00097 xlow = new double[n];
00098 xupp = new double[n];
00099 xmul = new double[n];
00100 xstate = new int[n];
00101
00102 F = new double[neF];
00103 Flow = new double[neF];
00104 Fupp = new double[neF];
00105 Fmul = new double[neF];
00106 Fstate = new int[neF];
00107
00108
00109
00110 auto bounds_x = nlp_->GetBoundsOnOptimizationVariables();
00111 for (uint _n=0; _n<bounds_x.size(); ++_n) {
00112 xlow[_n] = bounds_x.at(_n).lower_;
00113 xupp[_n] = bounds_x.at(_n).upper_;
00114 xstate[_n] = 0;
00115 }
00116
00117
00118 int c = 0;
00119 if (nlp_->HasCostTerms()) {
00120 Flow[c] = -1e20; Fupp[c] = 1e20; Fmul[c] = 0.0;
00121 c++;
00122 }
00123
00124
00125 auto bounds_g = nlp_->GetBoundsOnConstraints();
00126 for (const auto& b : bounds_g) {
00127 Flow[c] = b.lower_; Fupp[c] = b.upper_; Fmul[c] = 0.0;
00128 c++;
00129 }
00130
00131
00132 VectorXd x_all = nlp_->GetVariableValues();
00133 Eigen::Map<VectorXd>(&x[0], x_all.rows()) = x_all;
00134
00135 ObjRow = nlp_->HasCostTerms()? 0 : -1;
00136 ObjAdd = 0.0;
00137
00138
00139 lenA = 0;
00140 neA = 0;
00141 iAfun = nullptr;
00142 jAvar = nullptr;
00143 A = nullptr;
00144
00145
00146 lenG = obj_count*n + nlp_->GetJacobianOfConstraints().nonZeros();
00147 iGfun = new int[lenG];
00148 jGvar = new int[lenG];
00149
00150
00151 neG=0;
00152
00153
00154 if(nlp_->HasCostTerms()) {
00155 for (int var=0; var<n; ++var) {
00156 iGfun[neG] = 0;
00157 jGvar[neG] = var;
00158 neG++;
00159 }
00160 }
00161
00162
00163 auto jac = nlp_->GetJacobianOfConstraints();
00164 for (int k=0; k<jac.outerSize(); ++k) {
00165 for (Jacobian::InnerIterator it(jac,k); it; ++it) {
00166 iGfun[neG] = it.row() + obj_count;
00167 jGvar[neG] = it.col();
00168 neG++;
00169 }
00170 }
00171
00172
00173 this->initialize("", 1);
00174
00175
00176 this->setWorkspace(neF,n,neA,neG);
00177
00178 }
00179
00180 void
00181 SnoptAdapter::ObjectiveAndConstraintFct (int* Status, int* n, double x[],
00182 int* needF, int* neF, double F[],
00183 int* needG, int* neG, double G[],
00184 char* cu, int* lencu, int iu[],
00185 int* leniu, double ru[], int* lenru)
00186 {
00187 if ( *needF > 0 ) {
00188 int i=0;
00189
00190
00191 if (nlp_->HasCostTerms())
00192 F[i++] = nlp_->EvaluateCostFunction(x);
00193
00194
00195 VectorXd g_eig = nlp_->EvaluateConstraints(x);
00196 Eigen::Map<VectorXd>(F+i, g_eig.rows()) = g_eig;
00197 }
00198
00199
00200 if ( *needG > 0 ) {
00201 int i=0;
00202
00203
00204 if (nlp_->HasCostTerms()) {
00205 Eigen::VectorXd grad = nlp_->EvaluateCostFunctionGradient(x);
00206 i = grad.rows();
00207 Eigen::Map<VectorXd>(G, i) = grad;
00208 }
00209
00210
00211 nlp_->EvalNonzerosOfJacobian(x, G+i);
00212 nlp_->SaveCurrent();
00213 }
00214 }
00215
00216 void
00217 SnoptAdapter::SetVariables ()
00218 {
00219 nlp_->SetVariables(x);
00220 }
00221
00222 }