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, double epsilon=std::numeric_limits< double >::epsilon())
 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...
 
const std::vector< VectorXd > & GetIterations () const
 Read access to the history of iterations. 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 123 of file problem.h.

Member Typedef Documentation

◆ Jacobian

Definition at line 126 of file problem.h.

◆ VecBound

Definition at line 125 of file problem.h.

◆ VectorXd

Definition at line 127 of file problem.h.

Constructor & Destructor Documentation

◆ Problem()

ifopt::Problem::Problem ( )

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

Definition at line 63 of file problem.cc.

◆ ~Problem()

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

Member Function Documentation

◆ AddConstraintSet()

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

◆ AddCostSet()

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

◆ AddVariableSet()

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

◆ ConvertToEigen()

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

Definition at line 228 of file problem.cc.

◆ EvalNonzerosOfJacobian()

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

◆ EvaluateConstraints()

Problem::VectorXd ifopt::Problem::EvaluateConstraints ( const double *  x)

Each constraint value g(x) for current optimization variables x.

Definition at line 153 of file problem.cc.

◆ EvaluateCostFunction()

double ifopt::Problem::EvaluateCostFunction ( const double *  x)

The scalar cost for current optimization variables x.

Definition at line 106 of file problem.cc.

◆ EvaluateCostFunctionGradient()

Problem::VectorXd ifopt::Problem::EvaluateCostFunctionGradient ( const double *  x,
bool  use_finite_difference_approximation = false,
double  epsilon = std::numeric_limits<double>::epsilon() 
)

The column-vector of derivatives of the cost w.r.t. each variable.

ipopt uses 10e-8 for their derivative check, but setting here to more precise https://coin-or.github.io/Ipopt/OPTIONS.html#OPT_derivative_test_perturbation

Definition at line 116 of file problem.cc.

◆ GetBoundsOnConstraints()

Problem::VecBound ifopt::Problem::GetBoundsOnConstraints ( ) const

The upper and lower bound of each individual constraint.

Definition at line 143 of file problem.cc.

◆ GetBoundsOnOptimizationVariables()

Problem::VecBound ifopt::Problem::GetBoundsOnOptimizationVariables ( ) const

The maximum and minimum value each optimization variable is allowed to have.

Definition at line 91 of file problem.cc.

◆ GetConstraints()

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

Read access to the constraints composite.

Returns
A const reference to constraints_

Definition at line 281 of file problem.h.

◆ GetCosts()

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

Read access to the costs composite.

Returns
A const reference to costs_

Definition at line 287 of file problem.h.

◆ GetIterationCount()

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

The number of iterations it took to solve the problem.

Definition at line 270 of file problem.h.

◆ GetIterations()

const std::vector<VectorXd>& ifopt::Problem::GetIterations ( ) const
inline

Read access to the history of iterations.

Returns
A const reference to x_prev

Definition at line 293 of file problem.h.

◆ GetJacobianOfConstraints()

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

◆ GetJacobianOfCosts()

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

◆ GetNumberOfConstraints()

int ifopt::Problem::GetNumberOfConstraints ( ) const

The number of individual constraints.

Definition at line 148 of file problem.cc.

◆ GetNumberOfOptimizationVariables()

int ifopt::Problem::GetNumberOfOptimizationVariables ( ) const

The number of optimization variables.

Definition at line 86 of file problem.cc.

◆ GetOptVariables()

Composite::Ptr ifopt::Problem::GetOptVariables ( ) const

Read/write access to the current optimization variables.

Definition at line 188 of file problem.cc.

◆ GetVariableValues()

Problem::VectorXd ifopt::Problem::GetVariableValues ( ) const

The current value of the optimization variables.

Definition at line 96 of file problem.cc.

◆ HasCostTerms()

bool ifopt::Problem::HasCostTerms ( ) const

True if the optimization problem includes a cost, false if merely a feasibility problem is defined.

Definition at line 159 of file problem.cc.

◆ PrintCurrent()

void ifopt::Problem::PrintCurrent ( ) const

Prints the variables, costs and constraints.

Definition at line 203 of file problem.cc.

◆ SaveCurrent()

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

◆ SetOptVariables()

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

Sets the optimization variables to those at iteration iter.

Definition at line 193 of file problem.cc.

◆ SetOptVariablesFinal()

void ifopt::Problem::SetOptVariablesFinal ( )

Sets the optimization variables to those of the final iteration.

Definition at line 198 of file problem.cc.

◆ SetVariables()

void ifopt::Problem::SetVariables ( const double *  x)

Updates the variables with the values of the raw pointer x.

Definition at line 101 of file problem.cc.

Member Data Documentation

◆ constraints_

Composite ifopt::Problem::constraints_
private

Definition at line 297 of file problem.h.

◆ costs_

Composite ifopt::Problem::costs_
private

Definition at line 298 of file problem.h.

◆ variables_

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

Definition at line 293 of file problem.h.

◆ x_prev

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

the pure variables for every iteration.

Definition at line 300 of file problem.h.


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


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