51 using Eigen::Vector2d;
86 bounds.at(0) =
Bounds(-1.0, 1.0);
108 Vector2d x = GetVariables()->GetComponent(
"var_set1")->GetValues();
109 g(0) = std::pow(x(0),2) + x(1);
119 b.at(0) =
Bounds(1.0, 1.0);
134 if (var_set ==
"var_set1") {
136 Vector2d x = GetVariables()->GetComponent(
"var_set1")->GetValues();
138 jac_block.coeffRef(0, 0) = 2.0*x(0);
139 jac_block.coeffRef(0, 1) = 1.0;
152 Vector2d x = GetVariables()->GetComponent(
"var_set1")->GetValues();
153 return -std::pow(x(1)-2,2);
158 if (var_set ==
"var_set1") {
160 Vector2d x = GetVariables()->GetComponent(
"var_set1")->GetValues();
162 jac.coeffRef(0, 0) = 0.0;
163 jac.coeffRef(0, 1) = -2.0*(x(1)-2.0);
A container holding a single cost term.
ExVariables(const std::string &name)
A container holding a set of related constraints.
virtual VectorXd GetValues() const override
Returns the "values" of whatever this component represents.
virtual void SetVariables(const VectorXd &x) override
Sets the optimization variables from an Eigen vector.
void FillJacobianBlock(std::string var_set, Jacobian &jac_block) const override
Set individual Jacobians corresponding to each decision variable set.
VecBound GetBounds() const override
Returns the "bounds" of this component.
ExCost(const std::string &name)
static const Bounds NoBound
virtual VectorXd GetValues() const override
Returns the "values" of whatever this component represents.
virtual double GetCost() const override
Returns the scalar cost term calculated from the variables.
Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
Upper and lower bound for optimization variables and constraints.
VecBound GetBounds() const override
Returns the "bounds" of this component.
A container holding a set of related optimization variables.
ExConstraint(const std::string &name)
void FillJacobianBlock(std::string var_set, Jacobian &jac) const override
Set individual Jacobians corresponding to each decision variable set.
std::vector< Bounds > VecBound
int GetRows() const
Returns the number of rows of this component.