snopt76_adapter.cc
Go to the documentation of this file.
00001 /******************************************************************************
00002 Copyright (c) 2017, Alexander W. Winkler, ETH Zurich. All rights reserved.
00003 
00004 Redistribution and use in source and binary forms, with or without modification,
00005 are permitted provided that the following conditions are met:
00006     * Redistributions of source code must retain the above copyright notice,
00007       this list of conditions and the following disclaimer.
00008     * Redistributions in binary form must reproduce the above copyright notice,
00009       this list of conditions and the following disclaimer in the documentation
00010       and/or other materials provided with the distribution.
00011     * Neither the name of ETH ZURICH nor the names of its contributors may be
00012       used to endorse or promote products derived from this software without
00013       specific prior written permission.
00014 
00015 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00016 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00017 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00018 DISCLAIMED. IN NO EVENT SHALL ETH ZURICH BE LIABLE FOR ANY DIRECT, INDIRECT,
00019 INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00020 LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
00021 PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00022 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00023 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00024 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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   // error codes as given in the manual.
00041   int Cold = 0; // Basis = 1, Warm = 2;
00042 
00043   // new interface for 'Solve' using SNOPT76
00044   int nS = 0; // number of super-basic variables (not relevant for cold start)
00045   int nInf;   // nInf : number of constraints outside of the bounds
00046   double sInf;// sInf : sum of infeasibilities
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; // change least significant digit to zero
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   // A complete list of options can be found in the snopt user guide:
00070   // https://web.stanford.edu/group/SOL/guides/sndoc7.pdf
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 ); // 1 = snopt will not calculate missing derivatives
00077   solver.setIntParameter( "Verify level ", 3 ); // full check on gradients, will throw error
00078   solver.setIntParameter("Iterations limit", 200000);
00079   solver.setRealParameter( "Major feasibility tolerance",  1.0e-3); // target nonlinear constraint violation
00080   solver.setRealParameter( "Minor feasibility tolerance",  1.0e-3); // for satisfying the QP bounds
00081   solver.setRealParameter( "Major optimality tolerance",   1.0e-2); // target complementarity gap
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   // Set the upper and lower bounds.
00109   // no bounds on the spline coefficients or footholds
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   // bounds on the cost function if it exists
00118   int c = 0;
00119   if (nlp_->HasCostTerms()) {
00120     Flow[c] = -1e20; Fupp[c] = 1e20; Fmul[c] = 0.0; // no bounds on cost function
00121     c++;
00122   }
00123 
00124   // bounds on equality and inequality constraints
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   // initial values of the optimization
00132   VectorXd x_all = nlp_->GetVariableValues();
00133   Eigen::Map<VectorXd>(&x[0], x_all.rows()) = x_all;
00134 
00135   ObjRow  = nlp_->HasCostTerms()? 0 : -1; // the row in user function that corresponds to the objective function
00136   ObjAdd  = 0.0;                          // the constant to be added to the objective function
00137 
00138   // no linear derivatives/just assume all are nonlinear
00139   lenA = 0;
00140   neA = 0;
00141   iAfun = nullptr;
00142   jAvar = nullptr;
00143   A = nullptr;
00144 
00145   // derivatives of nonlinear part
00146   lenG  = obj_count*n + nlp_->GetJacobianOfConstraints().nonZeros();
00147   iGfun = new int[lenG];
00148   jGvar = new int[lenG];
00149 
00150   // the gradient terms of the cost function
00151   neG=0; // nonzero cells in jacobian of Cost Function AND Constraints
00152 
00153   // the nonzero elements of cost function (assume all)
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   // the nonzero elements of constraints (assume all)
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   // Snopt76 requires initialization
00173   this->initialize("", 1); // no print_file and summary ON
00174 
00175   // Snopt76 needs to setup the workspace
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     // the scalar objective function value
00191     if (nlp_->HasCostTerms())
00192       F[i++] = nlp_->EvaluateCostFunction(x);
00193 
00194     // the vector of constraint values
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     // the jacobian of the first row (cost function)
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     // the jacobian of all the constraints
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 } /* namespace opt */


ifopt_snopt
Author(s): Alexander W. Winkler
autogenerated on Sat Apr 21 2018 03:01:50