problem.cc
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2017, Alexander W Winkler. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without
5 modification, are permitted provided that the following conditions are met:
6 
7 * Redistributions of source code must retain the above copyright notice, this
8  list of conditions and the following disclaimer.
9 
10 * Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 
14 * Neither the name of the copyright holder nor the names of its
15  contributors may be used to endorse or promote products derived from
16  this software without specific prior written permission.
17 
18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 ******************************************************************************/
29 
30 #include <ifopt/problem.h>
31 #include <iostream>
32 #include <iomanip>
33 
34 
35 namespace ifopt {
36 
38  :constraints_("constraint-sets", false),
39  costs_("cost-terms", true)
40 {
41  variables_ = std::make_shared<Composite>("variable-sets", false);
42 }
43 
44 void
46 {
47  variables_->AddComponent(variable_set);
48 }
49 
50 void
52 {
53  constraint_set->LinkWithVariables(variables_);
54  constraints_.AddComponent(constraint_set);
55 }
56 
57 void
59 {
60  cost_set->LinkWithVariables(variables_);
61  costs_.AddComponent(cost_set);
62 }
63 
64 int
66 {
67  return variables_->GetRows();
68 }
69 
72 {
73  return variables_->GetBounds();
74 }
75 
78 {
79  return variables_->GetValues();
80 }
81 
82 void
83 Problem::SetVariables (const double* x)
84 {
85  variables_->SetVariables(ConvertToEigen(x));
86 }
87 
88 double
90 {
91  VectorXd g = VectorXd::Zero(1);
92  if (HasCostTerms()) {
93  SetVariables(x);
94  g = costs_.GetValues();
95  }
96  return g(0);
97 }
98 
100 Problem::EvaluateCostFunctionGradient (const double* x, bool use_finite_difference_approximation)
101 {
103  Jacobian jac = Jacobian(1,n);
104  if (HasCostTerms()) {
105  if(use_finite_difference_approximation) {
106  // ipopt uses 10e-8 for their derivative check.
107  // https://coin-or.github.io/Ipopt/OPTIONS.html#OPT_derivative_test_perturbation
108  // setting here to more precise, but can be adapted
109  double step_size = std::numeric_limits<double>::epsilon();
110 
111  // calculate forward difference by disturbing each optimization variable
112  double g = EvaluateCostFunction(x);
113  std::vector<double> x_new(x, x + n);
114  for (int i=0; i<n; ++i) {
115  x_new[i] += step_size; // disturb
116  double g_new = EvaluateCostFunction(x_new.data());
117  jac.coeffRef(0,i) = (g_new - g)/step_size;
118  x_new[i] -= step_size; // reset for next iteration
119  }
120  } else {
121  SetVariables(x);
122  jac = costs_.GetJacobian();
123  }
124  }
125 
126  return jac.row(0).transpose();
127 }
128 
131 {
132  return constraints_.GetBounds();
133 }
134 
135 int
137 {
138  return GetBoundsOnConstraints().size();
139 }
140 
143 {
144  SetVariables(x);
145  return constraints_.GetValues();
146 }
147 
148 bool
150 {
151  return costs_.GetRows()>0;
152 }
153 
154 void
155 Problem::EvalNonzerosOfJacobian (const double* x, double* values)
156 {
157  SetVariables(x);
159 
160  jac.makeCompressed(); // so the valuePtr() is dense and accurate
161  std::copy(jac.valuePtr(), jac.valuePtr() + jac.nonZeros(), values);
162 }
163 
166 {
167  return constraints_.GetJacobian();
168 }
169 
172 {
173  return costs_.GetJacobian();
174 }
175 
176 void
178 {
179  x_prev.push_back(variables_->GetValues());
180 }
181 
184 {
185  return variables_;
186 }
187 
188 void
190 {
191  variables_->SetVariables(x_prev.at(iter));
192 }
193 
194 void
196 {
197  variables_->SetVariables(x_prev.at(GetIterationCount()-1));
198 }
199 
200 void
202 {
203  using namespace std;
204  cout << "\n"
205  << "************************************************************\n"
206  << " IFOPT - Interface to Nonlinear Optimizers (v2.0)\n"
207  << " \u00a9 Alexander W. Winkler\n"
208  << " https://github.com/ethz-adrl/ifopt\n"
209  << "************************************************************"
210  << "\n"
211  << "Legend:\n"
212  << "c - number of variables, constraints or cost terms" << std::endl
213  << "i - indices of this set in overall problem" << std::endl
214  << "v - number of [violated variable- or constraint-bounds] or [cost term value]"
215  << "\n\n"
216  << std::right
217  << std::setw(33) << ""
218  << std::setw(5) << "c "
219  << std::setw(16) << "i "
220  << std::setw(11) << "v "
221  << std::left
222  << "\n";
223 
224  variables_->PrintAll();
226  costs_.PrintAll();
227 };
228 
230 Problem::ConvertToEigen(const double* x) const
231 {
232  return Eigen::Map<const VectorXd>(x,GetNumberOfOptimizationVariables());
233 }
234 
235 } /* namespace opt */
236 
std::vector< VectorXd > x_prev
the pure variables for every iteration.
Definition: problem.h:264
Problem()
Creates a optimization problem with no variables, costs or constraints.
Definition: problem.cc:37
Composite::Ptr variables_
Definition: problem.h:257
VecBound GetBounds() const override
Returns the "bounds" of this component.
Definition: composite.cc:194
void SetOptVariables(int iter)
Sets the optimization variables to those at iteration iter.
Definition: problem.cc:189
int GetIterationCount() const
The number of iterations it took to solve the problem.
Definition: problem.h:240
void AddCostSet(CostTerm::Ptr cost_set)
Add a cost term to the optimization problem.
Definition: problem.cc:58
std::shared_ptr< Composite > Ptr
Definition: composite.h:164
Component::Jacobian Jacobian
Definition: problem.h:100
void PrintAll() const
Definition: composite.cc:212
VecBound GetBoundsOnConstraints() const
The upper and lower bound of each individual constraint.
Definition: problem.cc:130
double EvaluateCostFunction(const double *x)
The scalar cost for current optimization variables x.
Definition: problem.cc:89
Composite constraints_
Definition: problem.h:261
VectorXd GetVariableValues() const
The current value of the optimization variables.
Definition: problem.cc:77
Component::VectorXd VectorXd
Definition: problem.h:101
std::shared_ptr< Component > Ptr
Definition: composite.h:65
void SaveCurrent()
Saves the current values of the optimization variables in x_prev.
Definition: problem.cc:177
bool HasCostTerms() const
True if the optimization problem includes a cost, false if merely a feasibility problem is defined...
Definition: problem.cc:149
VecBound GetBoundsOnOptimizationVariables() const
The maximum and minimum value each optimization variable is allowed to have.
Definition: problem.cc:71
Component::VecBound VecBound
Definition: problem.h:99
void PrintCurrent() const
Prints the variables, costs and constraints.
Definition: problem.cc:201
VectorXd GetValues() const override
Returns the "values" of whatever this component represents.
Definition: composite.cc:136
void SetVariables(const double *x)
Updates the variables with the values of the raw pointer x.
Definition: problem.cc:83
void AddComponent(const Component::Ptr &)
Adds a component to this composite.
Definition: composite.cc:104
Jacobian GetJacobianOfConstraints() const
The sparse-matrix representation of Jacobian of the constraints.
Definition: problem.cc:165
std::shared_ptr< ConstraintSet > Ptr
Jacobian GetJacobianOfCosts() const
The sparse-matrix representation of Jacobian of the costs.
Definition: problem.cc:171
void SetOptVariablesFinal()
Sets the optimization variables to those of the final iteration.
Definition: problem.cc:195
common namespace for all elements in this library.
Definition: bounds.h:33
Jacobian GetJacobian() const override
Returns derivatives of each row w.r.t. the variables.
Definition: composite.cc:164
void EvalNonzerosOfJacobian(const double *x, double *values)
Extracts those entries from constraint Jacobian that are not zero.
Definition: problem.cc:155
VectorXd ConvertToEigen(const double *x) const
Definition: problem.cc:230
void AddConstraintSet(ConstraintSet::Ptr constraint_set)
Add a set of multiple constraints to the optimization problem.
Definition: problem.cc:51
int GetNumberOfConstraints() const
The number of individual constraints.
Definition: problem.cc:136
VectorXd EvaluateConstraints(const double *x)
Each constraint value g(x) for current optimization variables x.
Definition: problem.cc:142
void AddVariableSet(VariableSet::Ptr variable_set)
Add one individual set of variables to the optimization problem.
Definition: problem.cc:45
Composite costs_
Definition: problem.h:262
int GetRows() const
Returns the number of rows of this component.
Definition: composite.cc:44
VectorXd EvaluateCostFunctionGradient(const double *x, bool use_finite_difference_approximation=false)
The column-vector of derivatives of the cost w.r.t. each variable.
Definition: problem.cc:100
Composite::Ptr GetOptVariables() const
Read/write access to the current optimization variables.
Definition: problem.cc:183
int GetNumberOfOptimizationVariables() const
The number of optimization variables.
Definition: problem.cc:65


ifopt
Author(s): Alexander W. Winkler
autogenerated on Fri Jan 22 2021 03:47:32