A container holding a set of related constraints. More...
#include <constraint_set.h>
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... | |
virtual void | FillJacobianBlock (std::string var_set, Jacobian &jac_block) const =0 |
Set individual Jacobians corresponding to each decision variable set. 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 | 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 |
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.
Definition at line 51 of file constraint_set.h.
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.
ifopt::ConstraintSet::ConstraintSet | ( | int | n_constraints, |
const std::string & | name | ||
) |
|
virtualdefault |
|
pure virtual |
Set individual Jacobians corresponding to each decision variable set.
var_set | Set of variables the current Jacobian block belongs to. |
jac_block | Columns 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.
Attention: jac_bock
is a sparse matrix, and must always have the same sparsity pattern. Therefore, it's better not to build a dense matrix and call .sparseView(), because if some entries happen to be zero for some iteration, that changes the sparsity pattern. A more robust way is to directly set as follows (which can also be set =0.0 without erros): jac_block.coeffRef(1, 3) = ...
Implemented in ifopt::ExCost, and ifopt::ExConstraint.
|
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.
|
inlineprotected |
Read access to the value of the optimization variables.
This must be used to formulate the constraint violation and Jacobian.
Definition at line 115 of file constraint_set.h.
|
inlineprivatevirtual |
Initialize quantities that depend on the optimization variables.
x | A 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 128 of file constraint_set.h.
void ifopt::ConstraintSet::LinkWithVariables | ( | const VariablesPtr & | 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 131 of file constraint_set.h.
|
private |
Definition at line 115 of file constraint_set.h.