snopt_adapter.cc
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2017, Alexander W. Winkler, ETH Zurich. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without modification,
5 are permitted provided that the following conditions are met:
6  * Redistributions of source code must retain the above copyright notice,
7  this list of conditions and the following disclaimer.
8  * Redistributions in binary form must reproduce the above copyright notice,
9  this list of conditions and the following disclaimer in the documentation
10  and/or other materials provided with the distribution.
11  * Neither the name of ETH ZURICH nor the names of its contributors may be
12  used to endorse or promote products derived from this software without
13  specific prior written permission.
14 
15 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
16 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
17 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
18 DISCLAIMED. IN NO EVENT SHALL ETH ZURICH BE LIABLE FOR ANY DIRECT, INDIRECT,
19 INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
20 LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
21 PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
22 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
23 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
24 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
25 ******************************************************************************/
26 
27 #include <ifopt/snopt_adapter.h>
28 
29 namespace ifopt {
30 
32 
33 SnoptAdapter::SnoptAdapter(Problem& ref)
34 {
35  nlp_ = &ref;
36 }
37 
38 void SnoptAdapter::Init()
39 {
40  int obj_count = nlp_->HasCostTerms() ? 1 : 0;
42  neF = nlp_->GetNumberOfConstraints() + obj_count;
43 
44  x = new double[n];
45  xlow = new double[n];
46  xupp = new double[n];
47  xmul = new double[n];
48  xstate = new int[n];
49 
50  F = new double[neF];
51  Flow = new double[neF];
52  Fupp = new double[neF];
53  Fmul = new double[neF];
54  Fstate = new int[neF];
55 
56  // Set the upper and lower bounds.
57  // no bounds on the spline coefficients or footholds
58  auto bounds_x = nlp_->GetBoundsOnOptimizationVariables();
59  for (std::size_t _n = 0; _n < bounds_x.size(); ++_n) {
60  xlow[_n] = bounds_x.at(_n).lower_;
61  xupp[_n] = bounds_x.at(_n).upper_;
62  xstate[_n] = 0;
63  }
64 
65  // bounds on the cost function if it exists
66  int c = 0;
67  if (nlp_->HasCostTerms()) {
68  Flow[c] = -1e20;
69  Fupp[c] = 1e20;
70  Fmul[c] = 0.0; // no bounds on cost function
71  c++;
72  }
73 
74  // bounds on equality and inequality constraints
75  auto bounds_g = nlp_->GetBoundsOnConstraints();
76  for (const auto& b : bounds_g) {
77  Flow[c] = b.lower_;
78  Fupp[c] = b.upper_;
79  Fmul[c] = 0.0;
80  c++;
81  }
82 
83  // initial values of the optimization
84  VectorXd x_all = nlp_->GetVariableValues();
85  Eigen::Map<VectorXd>(&x[0], x_all.rows()) = x_all;
86 
87  ObjRow =
89  ? 0
90  : -1; // the row in user function that corresponds to the objective function
91  ObjAdd = 0.0; // the constant to be added to the objective function
92 
93  // no linear derivatives/just assume all are nonlinear
94  lenA = 0;
95  neA = 0;
96  iAfun = nullptr;
97  jAvar = nullptr;
98  A = nullptr;
99 
100  // derivatives of nonlinear part
101  lenG = obj_count * n + nlp_->GetJacobianOfConstraints().nonZeros();
102  iGfun = new int[lenG];
103  jGvar = new int[lenG];
104 
105  // the gradient terms of the cost function
106  neG = 0; // nonzero cells in jacobian of Cost Function AND Constraints
107 
108  // the nonzero elements of cost function (assume all)
109  if (nlp_->HasCostTerms()) {
110  for (int var = 0; var < n; ++var) {
111  iGfun[neG] = 0;
112  jGvar[neG] = var;
113  neG++;
114  }
115  }
116 
117  // the nonzero elements of constraints (assume all)
118  auto jac = nlp_->GetJacobianOfConstraints();
119  for (int k = 0; k < jac.outerSize(); ++k) {
120  for (Jacobian::InnerIterator it(jac, k); it; ++it) {
121  iGfun[neG] = it.row() + obj_count;
122  jGvar[neG] = it.col();
123  neG++;
124  }
125  }
126 
128 }
129 
130 void SnoptAdapter::ObjectiveAndConstraintFct(int* Status, int* n, double x[],
131  int* needF, int* neF, double F[],
132  int* needG, int* neG, double G[],
133  char* cu, int* lencu, int iu[],
134  int* leniu, double ru[],
135  int* lenru)
136 {
137  if (*needF > 0) {
138  int i = 0;
139 
140  // the scalar objective function value
141  if (nlp_->HasCostTerms())
142  F[i++] = nlp_->EvaluateCostFunction(x);
143 
144  // the vector of constraint values
145  VectorXd g_eig = nlp_->EvaluateConstraints(x);
146  Eigen::Map<VectorXd>(F + i, g_eig.rows()) = g_eig;
147  }
148 
149  if (*needG > 0) {
150  int i = 0;
151 
152  // the jacobian of the first row (cost function)
153  if (nlp_->HasCostTerms()) {
154  Eigen::VectorXd grad = nlp_->EvaluateCostFunctionGradient(x, false);
155  i = grad.rows();
156  Eigen::Map<VectorXd>(G, i) = grad;
157  }
158 
159  // the jacobian of all the constraints
160  nlp_->EvalNonzerosOfJacobian(x, G + i);
161  nlp_->SaveCurrent();
162  }
163 }
164 
166 {
167  nlp_->SetVariables(x);
168 }
169 
170 } // namespace ifopt
ifopt::Problem::GetNumberOfOptimizationVariables
int GetNumberOfOptimizationVariables() const
The number of optimization variables.
Definition: problem.cc:86
ifopt::Problem::EvaluateCostFunction
double EvaluateCostFunction(const double *x)
The scalar cost for current optimization variables x.
Definition: problem.cc:106
ifopt::Problem::SetVariables
void SetVariables(const double *x)
Updates the variables with the values of the raw pointer x.
Definition: problem.cc:101
ifopt::Problem::EvaluateCostFunctionGradient
VectorXd EvaluateCostFunctionGradient(const double *x, bool use_finite_difference_approximation=false, double epsilon=std::numeric_limits< double >::epsilon())
The column-vector of derivatives of the cost w.r.t. each variable.
Definition: problem.cc:116
ifopt::Problem::GetBoundsOnConstraints
VecBound GetBoundsOnConstraints() const
The upper and lower bound of each individual constraint.
Definition: problem.cc:143
ifopt::SnoptAdapter::VectorXd
Problem::VectorXd VectorXd
Definition: snopt_adapter.h:99
ifopt::Problem::HasCostTerms
bool HasCostTerms() const
True if the optimization problem includes a cost, false if merely a feasibility problem is defined.
Definition: problem.cc:159
ifopt::SnoptAdapter::SetVariables
void SetVariables()
Definition: snopt_adapter.cc:189
ifopt::Problem::EvalNonzerosOfJacobian
void EvalNonzerosOfJacobian(const double *x, double *values)
Extracts those entries from constraint Jacobian that are not zero.
Definition: problem.cc:164
ifopt::Problem::GetNumberOfConstraints
int GetNumberOfConstraints() const
The number of individual constraints.
Definition: problem.cc:148
ifopt::Problem::GetJacobianOfConstraints
Jacobian GetJacobianOfConstraints() const
The sparse-matrix representation of Jacobian of the constraints.
Definition: problem.cc:173
ifopt::SnoptAdapter::nlp_
static NLPPtr nlp_
Definition: snopt_adapter.h:119
ifopt::SnoptAdapter::ObjectiveAndConstraintFct
static void ObjectiveAndConstraintFct(int *Status, int *n, double x[], int *needF, int *neF, double F[], int *needG, int *neG, double G[], char *cu, int *lencu, int iu[], int *leniu, double ru[], int *lenru)
Definition: snopt_adapter.cc:154
ifopt::Problem::EvaluateConstraints
VectorXd EvaluateConstraints(const double *x)
Each constraint value g(x) for current optimization variables x.
Definition: problem.cc:153
ifopt::Problem::GetVariableValues
VectorXd GetVariableValues() const
The current value of the optimization variables.
Definition: problem.cc:96
ifopt::SnoptAdapter::Init
void Init()
Definition: snopt_adapter.cc:62
ifopt::Problem::GetBoundsOnOptimizationVariables
VecBound GetBoundsOnOptimizationVariables() const
The maximum and minimum value each optimization variable is allowed to have.
Definition: problem.cc:91
ifopt::SnoptAdapter::NLPPtr
Problem * NLPPtr
Definition: snopt_adapter.h:98
ifopt
common namespace for all elements in this library.
Definition: bounds.h:33
snopt_adapter.h
ifopt::Problem::SaveCurrent
void SaveCurrent()
Saves the current values of the optimization variables in x_prev.
Definition: problem.cc:183
ifopt::SnoptAdapter::SnoptAdapter
SnoptAdapter(Problem &nlp)
Creates an Adapter Object around the problem to conform to the Snopt interface.
Definition: snopt_adapter.cc:57


ifopt
Author(s): Alexander W. Winkler
autogenerated on Mon Sep 18 2023 02:14:38