38 :constraints_(
"constraint-sets", false),
39 costs_(
"cost-terms", true)
41 variables_ = std::make_shared<Composite>(
"variable-sets",
false);
108 return jac.row(0).transpose();
142 jac.makeCompressed();
143 std::copy(jac.valuePtr(), jac.valuePtr() + jac.nonZeros(), values);
181 <<
"************************************************************\n" 182 <<
" IFOPT - Interface to Nonlinear Optimizers (v2.0)\n" 183 <<
" \u00a9 Alexander W. Winkler\n" 184 <<
" https://github.com/ethz-adrl/ifopt\n" 185 <<
"************************************************************" 188 <<
"c - number of variables, constraints or cost terms" << std::endl
189 <<
"i - indices of this set in overall problem" << std::endl
190 <<
"v - number of [violated variable- or constraint-bounds] or [cost term value]" 193 << std::setw(33) <<
"" 194 << std::setw(5) <<
"c " 195 << std::setw(16) <<
"i " 196 << std::setw(11) <<
"v " std::vector< VectorXd > x_prev
the pure variables for every iteration.
Problem()
Creates a optimization problem with no variables, costs or constraints.
Composite::Ptr variables_
VecBound GetBounds() const override
Returns the "bounds" of this component.
void SetOptVariables(int iter)
Sets the optimization variables to those at iteration iter.
int GetIterationCount() const
The number of iterations it took to solve the problem.
void AddCostSet(CostTerm::Ptr cost_set)
Add a cost term to the optimization problem.
std::shared_ptr< Composite > Ptr
Component::Jacobian Jacobian
VecBound GetBoundsOnConstraints() const
The upper and lower bound of each individual constraint.
double EvaluateCostFunction(const double *x)
The scalar cost for current optimization variables x.
VectorXd GetVariableValues() const
The current value of the optimization variables.
Component::VectorXd VectorXd
VectorXd EvaluateCostFunctionGradient(const double *x)
The column-vector of derivatives of the cost w.r.t. each variable.
std::shared_ptr< Component > Ptr
void SaveCurrent()
Saves the current values of the optimization variables in x_prev.
bool HasCostTerms() const
True if the optimization problem includes a cost, false if merely a feasibility problem is defined...
VecBound GetBoundsOnOptimizationVariables() const
The maximum and minimum value each optimization variable is allowed to have.
Component::VecBound VecBound
void PrintCurrent() const
Prints the variables, costs and constraints.
VectorXd GetValues() const override
Returns the "values" of whatever this component represents.
void SetVariables(const double *x)
Updates the variables with the values of the raw pointer x.
void AddComponent(const Component::Ptr &)
Adds a component to this composite.
Jacobian GetJacobianOfConstraints() const
The sparse-matrix representation of Jacobian of the constraints.
std::shared_ptr< ConstraintSet > Ptr
void SetOptVariablesFinal()
Sets the optimization variables to those of the final iteration.
common namespace for all elements in this library.
Jacobian GetJacobian() const override
Returns derivatives of each row w.r.t. the variables.
void EvalNonzerosOfJacobian(const double *x, double *values)
Extracts those entries from constraint Jacobian that are not zero.
VectorXd ConvertToEigen(const double *x) const
void AddConstraintSet(ConstraintSet::Ptr constraint_set)
Add a set of multiple constraints to the optimization problem.
int GetNumberOfConstraints() const
The number of individual constraints.
VectorXd EvaluateConstraints(const double *x)
Each constraint value g(x) for current optimization variables x.
void AddVariableSet(VariableSet::Ptr variable_set)
Add one individual set of variables to the optimization problem.
int GetRows() const
Returns the number of rows of this component.
Composite::Ptr GetOptVariables() const
Read/write access to the current optimization variables.
int GetNumberOfOptimizationVariables() const
The number of optimization variables.