Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
ifopt::Problem Class Reference

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, bool use_finite_difference_approximation=false)
 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...
 
const CompositeGetConstraints () const
 Read access to the constraints composite. More...
 
const CompositeGetCosts () const
 Read access to the costs composite. 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...
 
Jacobian GetJacobianOfCosts () const
 The sparse-matrix representation of Jacobian of the costs. 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< VectorXdx_prev
 the pure variables for every iteration. More...
 

Detailed Description

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.

Definition at line 97 of file problem.h.

Member Typedef Documentation

Definition at line 100 of file problem.h.

Definition at line 99 of file problem.h.

Definition at line 101 of file problem.h.

Constructor & Destructor Documentation

ifopt::Problem::Problem ( )

Creates a optimization problem with no variables, costs or constraints.

Definition at line 37 of file problem.cc.

virtual ifopt::Problem::~Problem ( )
virtualdefault

Member Function Documentation

void ifopt::Problem::AddConstraintSet ( ConstraintSet::Ptr  constraint_set)

Add a set of multiple constraints to the optimization problem.

Parameters
constraint_setThis 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.

Parameters
cost_setThe 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.

Parameters
variable_setThe 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.

Problem::VectorXd ifopt::Problem::ConvertToEigen ( const double *  x) const
private

Definition at line 230 of file problem.cc.

void ifopt::Problem::EvalNonzerosOfJacobian ( const double *  x,
double *  values 
)

Extracts those entries from constraint Jacobian that are not zero.

Parameters
[in]xThe current values of the optimization variables.
[out]valuesThe nonzero derivatives ordered by Eigen::RowMajor.

Definition at line 155 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 142 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,
bool  use_finite_difference_approximation = false 
)

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 130 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.

const Composite& ifopt::Problem::GetConstraints ( ) const
inline

Read access to the constraints composite.

Returns
A const reference to constraints_

Definition at line 251 of file problem.h.

const Composite& ifopt::Problem::GetCosts ( ) const
inline

Read access to the costs composite.

Returns
A const reference to costs_

Definition at line 257 of file problem.h.

int ifopt::Problem::GetIterationCount ( ) const
inline

The number of iterations it took to solve the problem.

Definition at line 240 of file problem.h.

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 165 of file problem.cc.

Problem::Jacobian ifopt::Problem::GetJacobianOfCosts ( ) const

The sparse-matrix representation of Jacobian of the costs.

Returns one row corresponding to the costs and each column corresponding to an optimizaton variable.

Definition at line 171 of file problem.cc.

int ifopt::Problem::GetNumberOfConstraints ( ) const

The number of individual constraints.

Definition at line 136 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 183 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 149 of file problem.cc.

void ifopt::Problem::PrintCurrent ( ) const

Prints the variables, costs and constraints.

Definition at line 201 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 177 of file problem.cc.

void ifopt::Problem::SetOptVariables ( int  iter)

Sets the optimization variables to those at iteration iter.

Definition at line 189 of file problem.cc.

void ifopt::Problem::SetOptVariablesFinal ( )

Sets the optimization variables to those of the final iteration.

Definition at line 195 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.

Member Data Documentation

Composite ifopt::Problem::constraints_
private

Definition at line 261 of file problem.h.

Composite ifopt::Problem::costs_
private

Definition at line 262 of file problem.h.

Composite::Ptr ifopt::Problem::variables_
private

Definition at line 257 of file problem.h.

std::vector<VectorXd> ifopt::Problem::x_prev
private

the pure variables for every iteration.

Definition at line 264 of file problem.h.


The documentation for this class was generated from the following files:


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