Public Member Functions | Private Member Functions | Private Attributes
ifopt::Problem Class Reference

A generic optimization problem with variables, costs and constraints. More...

#include <problem.h>

List of all members.

Public Member Functions

void AddConstraintSet (ConstraintSet::Ptr constraint_set)
 Add a set of multiple constraints to the optimization problem.
void AddCostSet (CostTerm::Ptr cost_set)
 Add a cost term to the optimization problem.
void AddVariableSet (VariableSet::Ptr variable_set)
 Add one individual set of variables to the optimization problem.
void EvalNonzerosOfJacobian (const double *x, double *values)
 Extracts those entries from constraint Jacobian that are not zero.
VectorXd EvaluateConstraints (const double *x)
 Each constraint value g(x) for current optimization variables x.
double EvaluateCostFunction (const double *x)
 The scalar cost for current optimization variables x.
VectorXd EvaluateCostFunctionGradient (const double *x)
 The column-vector of derivatives of the cost w.r.t. each variable.
VecBound GetBoundsOnConstraints () const
 The upper and lower bound of each individual constraint.
VecBound GetBoundsOnOptimizationVariables () const
 The maximum and minimum value each optimization variable is allowed to have.
int GetIterationCount () const
 The number of iterations it took to solve the problem.
Jacobian GetJacobianOfConstraints () const
 The sparse-matrix representation of Jacobian of the constraints.
int GetNumberOfConstraints () const
 The number of individual constraints.
int GetNumberOfOptimizationVariables () const
 The number of optimization variables.
Composite::Ptr GetOptVariables () const
 Read/write access to the current optimization variables.
VectorXd GetVariableValues () const
 The current value of the optimization variables.
bool HasCostTerms () const
 True if the optimization problem includes a cost, false if merely a feasibility problem is defined.
void PrintCurrent () const
 Prints the variables, costs and constraints.
 Problem ()
 Creates a optimization problem with no variables, costs or constraints.
void SaveCurrent ()
 Saves the current values of the optimization variables in x_prev.
void SetOptVariables (int iter)
 Sets the optimization variables to those at iteration iter.
void SetOptVariablesFinal ()
 Sets the optimization variables to those of the final iteration.
void SetVariables (const double *x)
 Updates the variables with the values of the raw pointer x.
virtual ~Problem ()

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.

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.

find x1, x2 (Variable sets 1 & 2) s.t x1_lower <= x1 <= x1_upper (bounds on variable set x1 R^m1)

g1_lower < g1(x1,x2) < g1_upper (Constraint set 1 R^n1) g2_lower < g2(x1,x2) < g2_upper (Constraint set 2 R^n2)

x1,x2 = arg min c1(x1,x2) (Cost terms 1)

See NLP solvers for currently implemented solvers.

Notice all the quantities (variables, cost, constraint) are represented by the same generic Component class.

Definition at line 62 of file problem.h.


Constructor & Destructor Documentation

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

Definition at line 35 of file problem.cc.

virtual ifopt::Problem::~Problem ( ) [virtual]

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 49 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 56 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 43 of file problem.cc.

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

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

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

The scalar cost for current optimization variables x.

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

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

The upper and lower bound of each individual constraint.

Definition at line 110 of file problem.cc.

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

Definition at line 69 of file problem.cc.

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

The number of iterations it took to solve the problem.

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

The number of individual constraints.

Definition at line 116 of file problem.cc.

The number of optimization variables.

Definition at line 63 of file problem.cc.

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

Read/write access to the current optimization variables.

Definition at line 157 of file problem.cc.

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

The current value of the optimization variables.

Definition at line 75 of file problem.cc.

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

Definition at line 129 of file problem.cc.

Prints the variables, costs and constraints.

Definition at line 175 of file problem.cc.

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

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

Sets the optimization variables to those at iteration iter.

Definition at line 163 of file problem.cc.

Sets the optimization variables to those of the final iteration.

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


Member Data Documentation

Definition at line 206 of file problem.h.

Definition at line 207 of file problem.h.

Composite::Ptr ifopt::Problem::variables_ [private]

Definition at line 205 of file problem.h.

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

the pure variables for every iteration.

Definition at line 209 of file problem.h.


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


ifopt_core
Author(s): Alexander W. Winkler
autogenerated on Sat Apr 21 2018 03:01:48