test_vars_constr_cost.h
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 
54 #include <ifopt/constraint_set.h>
55 #include <ifopt/cost_term.h>
56 #include <ifopt/variable_set.h>
57 
58 namespace ifopt {
59 using Eigen::Vector2d;
60 
61 class ExVariables : public VariableSet {
62  public:
63  // Every variable set has a name, here "var_set1". this allows the constraints
64  // and costs to define values and Jacobians specifically w.r.t this variable set.
65  ExVariables() : ExVariables("var_set1"){};
66  ExVariables(const std::string& name) : VariableSet(2, name)
67  {
68  // the initial values where the NLP starts iterating from
69  x0_ = 3.5;
70  x1_ = 1.5;
71  }
72 
73  // Here is where you can transform the Eigen::Vector into whatever
74  // internal representation of your variables you have (here two doubles, but
75  // can also be complex classes such as splines, etc..
76  void SetVariables(const VectorXd& x) override
77  {
78  x0_ = x(0);
79  x1_ = x(1);
80  };
81 
82  // Here is the reverse transformation from the internal representation to
83  // to the Eigen::Vector
84  VectorXd GetValues() const override { return Vector2d(x0_, x1_); };
85 
86  // Each variable has an upper and lower bound set here
87  VecBound GetBounds() const override
88  {
89  VecBound bounds(GetRows());
90  bounds.at(0) = Bounds(-1.0, 1.0);
91  bounds.at(1) = NoBound;
92  return bounds;
93  }
94 
95  private:
96  double x0_, x1_;
97 };
98 
99 class ExConstraint : public ConstraintSet {
100  public:
101  ExConstraint() : ExConstraint("constraint1") {}
102 
103  // This constraint set just contains 1 constraint, however generally
104  // each set can contain multiple related constraints.
105  ExConstraint(const std::string& name) : ConstraintSet(1, name) {}
106 
107  // The constraint value minus the constant value "1", moved to bounds.
108  VectorXd GetValues() const override
109  {
110  VectorXd g(GetRows());
111  Vector2d x = GetVariables()->GetComponent("var_set1")->GetValues();
112  g(0) = std::pow(x(0), 2) + x(1);
113  return g;
114  };
115 
116  // The only constraint in this set is an equality constraint to 1.
117  // Constant values should always be put into GetBounds(), not GetValues().
118  // For inequality constraints (<,>), use Bounds(x, inf) or Bounds(-inf, x).
119  VecBound GetBounds() const override
120  {
121  VecBound b(GetRows());
122  b.at(0) = Bounds(1.0, 1.0);
123  return b;
124  }
125 
126  // This function provides the first derivative of the constraints.
127  // In case this is too difficult to write, you can also tell the solvers to
128  // approximate the derivatives by finite differences and not overwrite this
129  // function, e.g. in ipopt.cc::use_jacobian_approximation_ = true
130  // Attention: see the parent class function for important information on sparsity pattern.
131  void FillJacobianBlock(std::string var_set,
132  Jacobian& jac_block) const override
133  {
134  // must fill only that submatrix of the overall Jacobian that relates
135  // to this constraint and "var_set1". even if more constraints or variables
136  // classes are added, this submatrix will always start at row 0 and column 0,
137  // thereby being independent from the overall problem.
138  if (var_set == "var_set1") {
139  Vector2d x = GetVariables()->GetComponent("var_set1")->GetValues();
140 
141  jac_block.coeffRef(0, 0) =
142  2.0 * x(0); // derivative of first constraint w.r.t x0
143  jac_block.coeffRef(0, 1) =
144  1.0; // derivative of first constraint w.r.t x1
145  }
146  }
147 };
148 
149 class ExCost : public CostTerm {
150  public:
151  ExCost() : ExCost("cost_term1") {}
152  ExCost(const std::string& name) : CostTerm(name) {}
153 
154  double GetCost() const override
155  {
156  Vector2d x = GetVariables()->GetComponent("var_set1")->GetValues();
157  return -std::pow(x(1) - 2, 2);
158  };
159 
160  void FillJacobianBlock(std::string var_set, Jacobian& jac) const override
161  {
162  if (var_set == "var_set1") {
163  Vector2d x = GetVariables()->GetComponent("var_set1")->GetValues();
164 
165  jac.coeffRef(0, 0) = 0.0; // derivative of cost w.r.t x0
166  jac.coeffRef(0, 1) = -2.0 * (x(1) - 2.0); // derivative of cost w.r.t x1
167  }
168  }
169 };
170 
171 } // namespace ifopt
ifopt::ExVariables::ExVariables
ExVariables()
Definition: test_vars_constr_cost.h:65
ifopt::ExVariables::GetValues
VectorXd GetValues() const override
Returns the "values" of whatever this component represents.
Definition: test_vars_constr_cost.h:84
ifopt::ConstraintSet::GetVariables
const VariablesPtr GetVariables() const
Read access to the value of the optimization variables.
Definition: constraint_set.h:170
ifopt::ExCost::ExCost
ExCost()
Definition: test_vars_constr_cost.h:151
ifopt::ExConstraint::ExConstraint
ExConstraint()
Definition: test_vars_constr_cost.h:101
ifopt::ExCost::GetCost
double GetCost() const override
Returns the scalar cost term calculated from the variables.
Definition: test_vars_constr_cost.h:154
ifopt::ExVariables::x0_
double x0_
Definition: test_vars_constr_cost.h:96
ifopt::ExVariables::GetBounds
VecBound GetBounds() const override
Returns the "bounds" of this component.
Definition: test_vars_constr_cost.h:87
ifopt::Component::VecBound
std::vector< Bounds > VecBound
Definition: composite.h:69
ifopt::ExCost::FillJacobianBlock
void FillJacobianBlock(std::string var_set, Jacobian &jac) const override
Set individual Jacobians corresponding to each decision variable set.
Definition: test_vars_constr_cost.h:160
ifopt::Bounds
Upper and lower bound for optimization variables and constraints.
Definition: bounds.h:65
ifopt::ExVariables::ExVariables
ExVariables(const std::string &name)
Definition: test_vars_constr_cost.h:66
constraint_set.h
cost_term.h
ifopt::ExVariables
Definition: test_vars_constr_cost.h:61
ifopt::ExVariables::SetVariables
void SetVariables(const VectorXd &x) override
Sets the optimization variables from an Eigen vector.
Definition: test_vars_constr_cost.h:76
ifopt::ExConstraint::GetBounds
VecBound GetBounds() const override
Returns the "bounds" of this component.
Definition: test_vars_constr_cost.h:119
variable_set.h
ifopt::ExConstraint
Definition: test_vars_constr_cost.h:99
ifopt
common namespace for all elements in this library.
Definition: bounds.h:33
ifopt::ConstraintSet
A container holding a set of related constraints.
Definition: constraint_set.h:78
ifopt::ExConstraint::GetValues
VectorXd GetValues() const override
Returns the "values" of whatever this component represents.
Definition: test_vars_constr_cost.h:108
ifopt::CostTerm
A container holding a single cost term.
Definition: cost_term.h:73
ifopt::VariableSet
A container holding a set of related optimization variables.
Definition: variable_set.h:73
ifopt::NoBound
static const Bounds NoBound
Definition: bounds.h:94
ifopt::Component::VectorXd
Eigen::VectorXd VectorXd
Definition: composite.h:68
ifopt::ExCost::ExCost
ExCost(const std::string &name)
Definition: test_vars_constr_cost.h:152
ifopt::Component::GetRows
int GetRows() const
Returns the number of rows of this component.
Definition: composite.cc:70
ifopt::ExCost
Definition: test_vars_constr_cost.h:149
ifopt::Component::Jacobian
Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
Definition: composite.h:67
ifopt::ExConstraint::FillJacobianBlock
void FillJacobianBlock(std::string var_set, Jacobian &jac_block) const override
Set individual Jacobians corresponding to each decision variable set.
Definition: test_vars_constr_cost.h:131
ifopt::ExConstraint::ExConstraint
ExConstraint(const std::string &name)
Definition: test_vars_constr_cost.h:105
ifopt::ExVariables::x1_
double x1_
Definition: test_vars_constr_cost.h:96


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