Public Types | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
ifopt::ConstraintSet Class Referenceabstract

A container holding a set of related constraints. More...

#include <constraint_set.h>

Inheritance diagram for ifopt::ConstraintSet:
Inheritance graph
[legend]

Public Types

using Ptr = std::shared_ptr< ConstraintSet >
 
using VariablesPtr = Composite::Ptr
 
- Public Types inherited from ifopt::Component
using Jacobian = Eigen::SparseMatrix< double, Eigen::RowMajor >
 
using Ptr = std::shared_ptr< Component >
 
using VecBound = std::vector< Bounds >
 
using VectorXd = Eigen::VectorXd
 

Public Member Functions

 ConstraintSet (int n_constraints, const std::string &name)
 Creates constraints on the variables x. More...
 
Jacobian GetJacobian () const final
 The matrix of derivatives for these constraints and variables. More...
 
void LinkWithVariables (const VariablesPtr &x)
 Connects the constraint with the optimization variables. More...
 
virtual ~ConstraintSet ()=default
 
- Public Member Functions inherited from ifopt::Component
 Component (int num_rows, const std::string &name)
 Creates a component. More...
 
virtual VecBound GetBounds () const =0
 Returns the "bounds" of this component. More...
 
std::string GetName () const
 Returns the name (id) of this component. More...
 
int GetRows () const
 Returns the number of rows of this component. More...
 
virtual VectorXd GetValues () const =0
 Returns the "values" of whatever this component represents. More...
 
virtual void Print (double tolerance, int &index_start) const
 Prints the relevant information (name, rows, values) of this component. More...
 
void SetRows (int num_rows)
 Sets the number of rows of this component. More...
 
virtual ~Component ()=default
 

Protected Member Functions

const VariablesPtr GetVariables () const
 Read access to the value of the optimization variables. More...
 

Private Member Functions

virtual void FillJacobianBlock (std::string var_set, Jacobian &jac_block) const =0
 Set individual Jacobians corresponding to each decision variable set. More...
 
virtual void InitVariableDependedQuantities (const VariablesPtr &x_init)
 Initialize quantities that depend on the optimization variables. More...
 
void SetVariables (const VectorXd &x) final
 Sets the optimization variables from an Eigen vector. More...
 

Private Attributes

VariablesPtr variables_
 

Additional Inherited Members

- Static Public Attributes inherited from ifopt::Component
static const int kSpecifyLater = -1
 

Detailed Description

A container holding a set of related constraints.

This container holds constraints representing a single concept, e.g. n constraints keeping a foot inside its range of motion. Each of the n rows is given by: lower_bound < g(x) < upper_bound

These constraint sets are later then stitched together to form the overall problem.

See also
Component

Definition at line 51 of file constraint_set.h.

Member Typedef Documentation

using ifopt::ConstraintSet::Ptr = std::shared_ptr<ConstraintSet>

Definition at line 53 of file constraint_set.h.

Definition at line 54 of file constraint_set.h.

Constructor & Destructor Documentation

ifopt::ConstraintSet::ConstraintSet ( int  n_constraints,
const std::string &  name 
)

Creates constraints on the variables x.

Parameters
n_constraintsThe number of constraints.
nameWhat these constraints represent.

Definition at line 45 of file leaves.cc.

virtual ifopt::ConstraintSet::~ConstraintSet ( )
virtualdefault

Member Function Documentation

virtual void ifopt::ConstraintSet::FillJacobianBlock ( std::string  var_set,
Jacobian jac_block 
) const
privatepure virtual

Set individual Jacobians corresponding to each decision variable set.

Parameters
var_setSet of variables the current Jacobian block belongs to.
jac_blockColumns of the overall Jacobian affected by var_set.

A convenience function so the user does not have to worry about the ordering of variable sets. All that is required is that the user knows the internal ordering of variables in each individual set and provides the Jacobian of the constraints w.r.t. this set (starting at column 0). GetJacobian() then inserts these columns at the correct position in the overall Jacobian.

If the constraint doen't depend on a var_set, this function should simply do nothing.

Implemented in ifopt::ExCost, and ifopt::ExConstraint.

ConstraintSet::Jacobian ifopt::ConstraintSet::GetJacobian ( ) const
finalvirtual

The matrix of derivatives for these constraints and variables.

Assuming n constraints and m variables, the returned Jacobian has dimensions n x m. Every row represents the derivatives of a single constraint, whereas every column refers to a single optimization variable.

This function only combines the user-defined jacobians from FillJacobianBlock().

Implements ifopt::Component.

Definition at line 51 of file leaves.cc.

const VariablesPtr ifopt::ConstraintSet::GetVariables ( ) const
inlineprotected

Read access to the value of the optimization variables.

This must be used to formulate the constraint violation and Jacobian.

Definition at line 91 of file constraint_set.h.

virtual void ifopt::ConstraintSet::InitVariableDependedQuantities ( const VariablesPtr x_init)
inlineprivatevirtual

Initialize quantities that depend on the optimization variables.

Parameters
xA pointer to the initial values of the optimization variables.

Sometimes the number of constraints depends on the variable representation, or shorthands to specific variable sets want to be saved for quicker access later. This function can be overwritten for that.

Definition at line 120 of file constraint_set.h.

void ifopt::ConstraintSet::LinkWithVariables ( const VariablesPtr x)

Connects the constraint with the optimization variables.

Parameters
xA pointer to the current values of the optimization variables.

The optimization variable values are necessary for calculating constraint violations and Jacobians.

Definition at line 80 of file leaves.cc.

void ifopt::ConstraintSet::SetVariables ( const VectorXd x)
inlinefinalprivatevirtual

Sets the optimization variables from an Eigen vector.

This is only done for Variable, where these are set from the current values of the solvers.

Implements ifopt::Component.

Definition at line 123 of file constraint_set.h.

Member Data Documentation

VariablesPtr ifopt::ConstraintSet::variables_
private

Definition at line 110 of file constraint_set.h.


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


ifopt
Author(s): Alexander W. Winkler
autogenerated on Fri May 17 2019 02:29:49