A generic optimization problem with variables, costs and constraints. More...
#include <problem.h>
Public Types | |
using | Jacobian = Component::Jacobian |
using | VecBound = Component::VecBound |
using | VectorXd = Component::VectorXd |
Public Member Functions | |
void | AddConstraintSet (ConstraintSet::Ptr constraint_set) |
Add a set of multiple constraints to the optimization problem. More... | |
void | AddCostSet (CostTerm::Ptr cost_set) |
Add a cost term to the optimization problem. More... | |
void | AddVariableSet (VariableSet::Ptr variable_set) |
Add one individual set of variables to the optimization problem. More... | |
void | EvalNonzerosOfJacobian (const double *x, double *values) |
Extracts those entries from constraint Jacobian that are not zero. More... | |
VectorXd | EvaluateConstraints (const double *x) |
Each constraint value g(x) for current optimization variables x . More... | |
double | EvaluateCostFunction (const double *x) |
The scalar cost for current optimization variables x . More... | |
VectorXd | EvaluateCostFunctionGradient (const double *x) |
The column-vector of derivatives of the cost w.r.t. each variable. More... | |
VecBound | GetBoundsOnConstraints () const |
The upper and lower bound of each individual constraint. More... | |
VecBound | GetBoundsOnOptimizationVariables () const |
The maximum and minimum value each optimization variable is allowed to have. More... | |
int | GetIterationCount () const |
The number of iterations it took to solve the problem. More... | |
Jacobian | GetJacobianOfConstraints () const |
The sparse-matrix representation of Jacobian of the constraints. More... | |
int | GetNumberOfConstraints () const |
The number of individual constraints. More... | |
int | GetNumberOfOptimizationVariables () const |
The number of optimization variables. More... | |
Composite::Ptr | GetOptVariables () const |
Read/write access to the current optimization variables. More... | |
VectorXd | GetVariableValues () const |
The current value of the optimization variables. More... | |
bool | HasCostTerms () const |
True if the optimization problem includes a cost, false if merely a feasibility problem is defined. More... | |
void | PrintCurrent () const |
Prints the variables, costs and constraints. More... | |
Problem () | |
Creates a optimization problem with no variables, costs or constraints. More... | |
void | SaveCurrent () |
Saves the current values of the optimization variables in x_prev. More... | |
void | SetOptVariables (int iter) |
Sets the optimization variables to those at iteration iter. More... | |
void | SetOptVariablesFinal () |
Sets the optimization variables to those of the final iteration. More... | |
void | SetVariables (const double *x) |
Updates the variables with the values of the raw pointer x . More... | |
virtual | ~Problem ()=default |
Private Member Functions | |
VectorXd | ConvertToEigen (const double *x) const |
Private Attributes | |
Composite | constraints_ |
Composite | costs_ |
Composite::Ptr | variables_ |
std::vector< VectorXd > | x_prev |
the pure variables for every iteration. More... | |
A generic optimization problem with variables, costs and constraints.
This class is responsible for holding all the information of an optimization problem, which includes the optimization variables, their variable bounds, the cost function, the constraints and their bounds and derivatives of all. With this information the problem can be solved by any specific solver. All the quantities (variables, cost, constraint) are represented by the same generic Component class.
See Solvers for currently implemented solvers.
ifopt::Problem::Problem | ( | ) |
Creates a optimization problem with no variables, costs or constraints.
Definition at line 37 of file problem.cc.
|
virtualdefault |
void ifopt::Problem::AddConstraintSet | ( | ConstraintSet::Ptr | constraint_set | ) |
Add a set of multiple constraints to the optimization problem.
constraint_set | This can be 1 to infinity number of constraints. |
This function can be called multiple times for different sets of constraints. It makes sure the overall constraint and Jacobian correctly considers all individual constraint sets.
Definition at line 51 of file problem.cc.
void ifopt::Problem::AddCostSet | ( | CostTerm::Ptr | cost_set | ) |
Add a cost term to the optimization problem.
cost_set | The calculation of the cost from the variables. |
This function can be called multiple times if the cost function is composed of different cost terms. It makes sure the overall value and gradient is considering each individual cost.
Definition at line 58 of file problem.cc.
void ifopt::Problem::AddVariableSet | ( | VariableSet::Ptr | variable_set | ) |
Add one individual set of variables to the optimization problem.
variable_set | The selection of optimization variables. |
This function can be called multiple times, with multiple sets, e.g. one set that parameterizes a body trajectory, the other that resembles the optimal timing values. This function correctly appends the individual variables sets and ensures correct order of Jacobian columns.
Definition at line 45 of file problem.cc.
|
private |
Definition at line 206 of file problem.cc.
void ifopt::Problem::EvalNonzerosOfJacobian | ( | const double * | x, |
double * | values | ||
) |
Extracts those entries from constraint Jacobian that are not zero.
[in] | x | The current values of the optimization variables. |
[out] | values | The nonzero derivatives ordered by Eigen::RowMajor. |
Definition at line 137 of file problem.cc.
Problem::VectorXd ifopt::Problem::EvaluateConstraints | ( | const double * | x | ) |
Each constraint value g(x) for current optimization variables x
.
Definition at line 124 of file problem.cc.
double ifopt::Problem::EvaluateCostFunction | ( | const double * | x | ) |
The scalar cost for current optimization variables x
.
Definition at line 89 of file problem.cc.
Problem::VectorXd ifopt::Problem::EvaluateCostFunctionGradient | ( | const double * | x | ) |
The column-vector of derivatives of the cost w.r.t. each variable.
Definition at line 100 of file problem.cc.
Problem::VecBound ifopt::Problem::GetBoundsOnConstraints | ( | ) | const |
The upper and lower bound of each individual constraint.
Definition at line 112 of file problem.cc.
Problem::VecBound ifopt::Problem::GetBoundsOnOptimizationVariables | ( | ) | const |
The maximum and minimum value each optimization variable is allowed to have.
Definition at line 71 of file problem.cc.
|
inline |
Problem::Jacobian ifopt::Problem::GetJacobianOfConstraints | ( | ) | const |
The sparse-matrix representation of Jacobian of the constraints.
Each row corresponds to a constraint and each column to an optimizaton variable.
Definition at line 147 of file problem.cc.
int ifopt::Problem::GetNumberOfConstraints | ( | ) | const |
The number of individual constraints.
Definition at line 118 of file problem.cc.
int ifopt::Problem::GetNumberOfOptimizationVariables | ( | ) | const |
The number of optimization variables.
Definition at line 65 of file problem.cc.
Composite::Ptr ifopt::Problem::GetOptVariables | ( | ) | const |
Read/write access to the current optimization variables.
Definition at line 159 of file problem.cc.
Problem::VectorXd ifopt::Problem::GetVariableValues | ( | ) | const |
The current value of the optimization variables.
Definition at line 77 of file problem.cc.
bool ifopt::Problem::HasCostTerms | ( | ) | const |
True if the optimization problem includes a cost, false if merely a feasibility problem is defined.
Definition at line 131 of file problem.cc.
void ifopt::Problem::PrintCurrent | ( | ) | const |
Prints the variables, costs and constraints.
Definition at line 177 of file problem.cc.
void ifopt::Problem::SaveCurrent | ( | ) |
Saves the current values of the optimization variables in x_prev.
This is used to keep a history of the values for each NLP iterations.
Definition at line 153 of file problem.cc.
void ifopt::Problem::SetOptVariables | ( | int | iter | ) |
Sets the optimization variables to those at iteration iter.
Definition at line 165 of file problem.cc.
void ifopt::Problem::SetOptVariablesFinal | ( | ) |
Sets the optimization variables to those of the final iteration.
Definition at line 171 of file problem.cc.
void ifopt::Problem::SetVariables | ( | const double * | x | ) |
Updates the variables with the values of the raw pointer x
.
Definition at line 83 of file problem.cc.
|
private |
|
private |