snopt_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_adapter.h>
00028 
00029 namespace ifopt {
00030 
00031 SnoptAdapter::NLPPtr SnoptAdapter::nlp_;
00032 
00033 SnoptAdapter::SnoptAdapter (Problem& ref)
00034 {
00035   nlp_ = &ref;
00036 }
00037 
00038 void
00039 SnoptAdapter::Init ()
00040 {
00041   int obj_count = nlp_->HasCostTerms()? 1 : 0;
00042   n     = nlp_->GetNumberOfOptimizationVariables();
00043   neF   = nlp_->GetNumberOfConstraints() + obj_count;
00044 
00045   x      = new double[n];
00046   xlow   = new double[n];
00047   xupp   = new double[n];
00048   xmul   = new double[n];
00049   xstate = new    int[n];
00050 
00051   F      = new double[neF];
00052   Flow   = new double[neF];
00053   Fupp   = new double[neF];
00054   Fmul   = new double[neF];
00055   Fstate = new    int[neF];
00056 
00057   // Set the upper and lower bounds.
00058   // no bounds on the spline coefficients or footholds
00059   auto bounds_x = nlp_->GetBoundsOnOptimizationVariables();
00060   for (uint _n=0; _n<bounds_x.size(); ++_n) {
00061     xlow[_n] = bounds_x.at(_n).lower_;
00062     xupp[_n] = bounds_x.at(_n).upper_;
00063     xstate[_n] = 0;
00064   }
00065 
00066   // bounds on the cost function if it exists
00067   int c = 0;
00068   if (nlp_->HasCostTerms()) {
00069     Flow[c] = -1e20; Fupp[c] = 1e20; Fmul[c] = 0.0; // no bounds on cost function
00070     c++;
00071   }
00072 
00073   // bounds on equality and inequality constraints
00074   auto bounds_g = nlp_->GetBoundsOnConstraints();
00075   for (const auto& b : bounds_g) {
00076     Flow[c] = b.lower_; Fupp[c] = b.upper_; Fmul[c] = 0.0;
00077     c++;
00078   }
00079 
00080   // initial values of the optimization
00081   VectorXd x_all = nlp_->GetVariableValues();
00082   Eigen::Map<VectorXd>(&x[0], x_all.rows()) = x_all;
00083 
00084   ObjRow  = nlp_->HasCostTerms()? 0 : -1; // the row in user function that corresponds to the objective function
00085   ObjAdd  = 0.0;                          // the constant to be added to the objective function
00086 
00087   // no linear derivatives/just assume all are nonlinear
00088   lenA = 0;
00089   neA = 0;
00090   iAfun = nullptr;
00091   jAvar = nullptr;
00092   A = nullptr;
00093 
00094   // derivatives of nonlinear part
00095   lenG  = obj_count*n + nlp_->GetJacobianOfConstraints().nonZeros();
00096   iGfun = new int[lenG];
00097   jGvar = new int[lenG];
00098 
00099   // the gradient terms of the cost function
00100   neG=0; // nonzero cells in jacobian of Cost Function AND Constraints
00101 
00102   // the nonzero elements of cost function (assume all)
00103   if(nlp_->HasCostTerms()) {
00104     for (int var=0; var<n; ++var) {
00105       iGfun[neG] = 0;
00106       jGvar[neG] = var;
00107       neG++;
00108     }
00109   }
00110 
00111   // the nonzero elements of constraints (assume all)
00112   auto jac = nlp_->GetJacobianOfConstraints();
00113   for (int k=0; k<jac.outerSize(); ++k) {
00114     for (Jacobian::InnerIterator it(jac,k); it; ++it) {
00115       iGfun[neG] = it.row() + obj_count;
00116       jGvar[neG] = it.col();
00117       neG++;
00118     }
00119   }
00120 
00121   setUserFun(&SnoptAdapter::ObjectiveAndConstraintFct);
00122 }
00123 
00124 void
00125 SnoptAdapter::ObjectiveAndConstraintFct (int* Status, int* n, double x[],
00126                                          int* needF, int* neF, double F[],
00127                                          int* needG, int* neG, double G[],
00128                                          char* cu, int* lencu, int iu[],
00129                                          int* leniu, double ru[], int* lenru)
00130 {
00131   if ( *needF > 0 ) {
00132     int i=0;
00133 
00134     // the scalar objective function value
00135     if (nlp_->HasCostTerms())
00136       F[i++] = nlp_->EvaluateCostFunction(x);
00137 
00138     // the vector of constraint values
00139     VectorXd g_eig = nlp_->EvaluateConstraints(x);
00140     Eigen::Map<VectorXd>(F+i, g_eig.rows()) = g_eig;
00141   }
00142 
00143 
00144   if ( *needG > 0 ) {
00145     int i=0;
00146 
00147     // the jacobian of the first row (cost function)
00148     if (nlp_->HasCostTerms()) {
00149       Eigen::VectorXd grad = nlp_->EvaluateCostFunctionGradient(x);
00150       i = grad.rows();
00151       Eigen::Map<VectorXd>(G, i) = grad;
00152     }
00153 
00154     // the jacobian of all the constraints
00155     nlp_->EvalNonzerosOfJacobian(x, G+i);
00156     nlp_->SaveCurrent();
00157   }
00158 }
00159 
00160 void
00161 SnoptAdapter::SetVariables ()
00162 {
00163   nlp_->SetVariables(x);
00164 }
00165 
00166 } /* namespace opt */


ifopt
Author(s): Alexander W. Winkler
autogenerated on Sat May 18 2019 02:43:08