Drake
Drake C++ Documentation
Loading...
Searching...
No Matches
LinearConstraint Class Reference

Detailed Description

Implements a constraint of the form \( lb <= Ax <= ub \).

#include <drake/solvers/constraint.h>

Public Member Functions

 LinearConstraint (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub)
 Construct the linear constraint lb <= A*x <= ub.
 LinearConstraint (const Eigen::SparseMatrix< double > &A, const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub)
 Overloads constructor with a sparse A matrix.
 ~LinearConstraint () override
const Eigen::SparseMatrix< double > & get_sparse_A () const
const Eigen::MatrixXd & GetDenseA () const
 Get the matrix A as a dense matrix.
void UpdateCoefficients (const Eigen::Ref< const Eigen::MatrixXd > &new_A, const Eigen::Ref< const Eigen::VectorXd > &new_lb, const Eigen::Ref< const Eigen::VectorXd > &new_ub)
 Updates the linear term, upper and lower bounds in the linear constraint.
void UpdateCoefficients (const Eigen::SparseMatrix< double > &new_A, const Eigen::Ref< const Eigen::VectorXd > &new_lb, const Eigen::Ref< const Eigen::VectorXd > &new_ub)
 Overloads UpdateCoefficients but with a sparse A matrix.
void RemoveTinyCoefficient (double tol)
 Sets A(i, j) to zero if abs(A(i, j)) <= tol.
bool is_dense_A_constructed () const
 Returns true iff this constraint already has a dense representation, i.e, if GetDenseA() will be cheap.
void set_bounds (const Eigen::Ref< const Eigen::VectorXd > &new_lb, const Eigen::Ref< const Eigen::VectorXd > &new_ub)
 Set the upper and lower bounds of the constraint.
void UpdateLowerBound (const Eigen::Ref< const Eigen::VectorXd > &new_lb)
 Updates the lower bound.
void UpdateUpperBound (const Eigen::Ref< const Eigen::VectorXd > &new_ub)
 Updates the upper bound.
Does not allow copy, move, or assignment
 LinearConstraint (const LinearConstraint &)=delete
 LinearConstraint (LinearConstraint &&)=delete
LinearConstraintoperator= (const LinearConstraint &)=delete
LinearConstraintoperator= (LinearConstraint &&)=delete
Public Member Functions inherited from Constraint
template<typename DerivedLB, typename DerivedUB>
 Constraint (int num_constraints, int num_vars, const Eigen::MatrixBase< DerivedLB > &lb, const Eigen::MatrixBase< DerivedUB > &ub, const std::string &description="")
 Constructs a constraint which has num_constraints rows, with an input num_vars x 1 vector.
 Constraint (int num_constraints, int num_vars)
 Constructs a constraint which has num_constraints rows, with an input num_vars x 1 vector, with no bounds.
bool CheckSatisfied (const Eigen::Ref< const Eigen::VectorXd > &x, double tol=1E-6) const
 Return whether this constraint is satisfied by the given value, x.
bool CheckSatisfied (const Eigen::Ref< const AutoDiffVecXd > &x, double tol=1E-6) const
symbolic::Formula CheckSatisfied (const Eigen::Ref< const VectorX< symbolic::Variable > > &x) const
const Eigen::VectorXd & lower_bound () const
const Eigen::VectorXd & upper_bound () const
int num_constraints () const
 Number of rows in the output constraint.
 Constraint (const Constraint &)=delete
Constraintoperator= (const Constraint &)=delete
 Constraint (Constraint &&)=delete
Constraintoperator= (Constraint &&)=delete
Public Member Functions inherited from EvaluatorBase
virtual ~EvaluatorBase ()
void Eval (const Eigen::Ref< const Eigen::VectorXd > &x, Eigen::VectorXd *y) const
 Evaluates the expression.
void Eval (const Eigen::Ref< const AutoDiffVecXd > &x, AutoDiffVecXd *y) const
 Evaluates the expression.
void Eval (const Eigen::Ref< const VectorX< symbolic::Variable > > &x, VectorX< symbolic::Expression > *y) const
 Evaluates the expression.
void set_description (const std::string &description)
 Set a human-friendly description for the evaluator.
const std::string & get_description () const
 Getter for a human-friendly description for the evaluator.
std::ostream & Display (std::ostream &os, const VectorX< symbolic::Variable > &vars) const
 Formats this evaluator into the given stream using vars for the bound decision variable names.
std::ostream & Display (std::ostream &os) const
 Formats this evaluator into the given stream, without displaying the decision variables it is bound to.
std::string ToLatex (const VectorX< symbolic::Variable > &vars, int precision=3) const
 Returns a LaTeX string describing this evaluator.
int num_vars () const
 Getter for the number of variables, namely the number of rows in x, as used in Eval(x, y).
int num_outputs () const
 Getter for the number of outputs, namely the number of rows in y, as used in Eval(x, y).
void SetGradientSparsityPattern (const std::vector< std::pair< int, int > > &gradient_sparsity_pattern)
 Set the sparsity pattern of the gradient matrix ∂y/∂x (the gradient of y value in Eval, w.r.t x in Eval) .
const std::optional< std::vector< std::pair< int, int > > > & gradient_sparsity_pattern () const
 Returns the vector of (row_index, col_index) that contains all the entries in the gradient of Eval function (∂y/∂x) whose value could be non-zero, namely if ∂yᵢ/∂xⱼ could be non-zero, then the pair (i, j) is in gradient_sparsity_pattern.
bool is_thread_safe () const
 Returns whether it is safe to call Eval in parallel.
 EvaluatorBase (const EvaluatorBase &)=delete
EvaluatorBaseoperator= (const EvaluatorBase &)=delete
 EvaluatorBase (EvaluatorBase &&)=delete
EvaluatorBaseoperator= (EvaluatorBase &&)=delete

Protected Member Functions

void DoEval (const Eigen::Ref< const Eigen::VectorXd > &x, Eigen::VectorXd *y) const override
 Implements expression evaluation for scalar type double.
void DoEval (const Eigen::Ref< const AutoDiffVecXd > &x, AutoDiffVecXd *y) const override
 Implements expression evaluation for scalar type AutoDiffXd.
void DoEval (const Eigen::Ref< const VectorX< symbolic::Variable > > &x, VectorX< symbolic::Expression > *y) const override
 Implements expression evaluation for scalar type symbolic::Expression.
std::ostream & DoDisplay (std::ostream &, const VectorX< symbolic::Variable > &) const override
 NVI implementation of Display.
std::string DoToLatex (const VectorX< symbolic::Variable > &, int) const override
Protected Member Functions inherited from Constraint
void UpdateLowerBound (const Eigen::Ref< const Eigen::VectorXd > &new_lb)
 Updates the lower bound.
void UpdateUpperBound (const Eigen::Ref< const Eigen::VectorXd > &new_ub)
 Updates the upper bound.
void set_bounds (const Eigen::Ref< const Eigen::VectorXd > &new_lb, const Eigen::Ref< const Eigen::VectorXd > &new_ub)
 Set the upper and lower bounds of the constraint.
virtual bool DoCheckSatisfied (const Eigen::Ref< const Eigen::VectorXd > &x, const double tol) const
virtual bool DoCheckSatisfied (const Eigen::Ref< const AutoDiffVecXd > &x, const double tol) const
virtual symbolic::Formula DoCheckSatisfied (const Eigen::Ref< const VectorX< symbolic::Variable > > &x) const
Protected Member Functions inherited from EvaluatorBase
 EvaluatorBase (int num_outputs, int num_vars, const std::string &description="")
 Constructs a evaluator.
void set_num_outputs (int num_outputs)
void set_is_thread_safe (bool is_thread_safe)

Protected Attributes

internal::SparseAndDenseMatrix A_

Constructor & Destructor Documentation

◆ LinearConstraint() [1/4]

LinearConstraint ( const LinearConstraint & )
delete

◆ LinearConstraint() [2/4]

◆ LinearConstraint() [3/4]

LinearConstraint ( const Eigen::Ref< const Eigen::MatrixXd > & A,
const Eigen::Ref< const Eigen::VectorXd > & lb,
const Eigen::Ref< const Eigen::VectorXd > & ub )

Construct the linear constraint lb <= A*x <= ub.

Throws if A has any entry which is not finite.

◆ LinearConstraint() [4/4]

LinearConstraint ( const Eigen::SparseMatrix< double > & A,
const Eigen::Ref< const Eigen::VectorXd > & lb,
const Eigen::Ref< const Eigen::VectorXd > & ub )

Overloads constructor with a sparse A matrix.

Throws if A has any entry which is not finite.

◆ ~LinearConstraint()

~LinearConstraint ( )
override

Member Function Documentation

◆ DoDisplay()

std::ostream & DoDisplay ( std::ostream & os,
const VectorX< symbolic::Variable > & vars ) const
overrideprotectedvirtual

NVI implementation of Display.

The default implementation will report the NiceTypeName, get_description, and list the bound variables. Subclasses may override to customize the message.

Precondition
vars size is consistent with num_vars".

Reimplemented from EvaluatorBase.

◆ DoEval() [1/3]

void DoEval ( const Eigen::Ref< const AutoDiffVecXd > & x,
AutoDiffVecXd * y ) const
overrideprotectedvirtual

Implements expression evaluation for scalar type AutoDiffXd.

Parameters
xInput vector.
yOutput vector.
Precondition
x must be of size num_vars x 1.
Postcondition
y will be of size num_outputs x 1.

Implements EvaluatorBase.

◆ DoEval() [2/3]

void DoEval ( const Eigen::Ref< const Eigen::VectorXd > & x,
Eigen::VectorXd * y ) const
overrideprotectedvirtual

Implements expression evaluation for scalar type double.

Parameters
xInput vector.
yOutput vector.
Precondition
x must be of size num_vars x 1.
Postcondition
y will be of size num_outputs x 1.

Implements EvaluatorBase.

◆ DoEval() [3/3]

void DoEval ( const Eigen::Ref< const VectorX< symbolic::Variable > > & x,
VectorX< symbolic::Expression > * y ) const
overrideprotectedvirtual

Implements expression evaluation for scalar type symbolic::Expression.

Parameters
[in]xInput vector.
[out]yOutput vector.
Precondition
x must be of size num_vars x 1.
Postcondition
y will be of size num_outputs x 1.

Implements EvaluatorBase.

◆ DoToLatex()

std::string DoToLatex ( const VectorX< symbolic::Variable > & ,
int  ) const
overrideprotectedvirtual

Reimplemented from EvaluatorBase.

◆ get_sparse_A()

const Eigen::SparseMatrix< double > & get_sparse_A ( ) const

◆ GetDenseA()

const Eigen::MatrixXd & GetDenseA ( ) const

Get the matrix A as a dense matrix.

Note
this might involve memory allocation to convert a sparse matrix to a dense one, for better performance you should call get_sparse_A() which returns a sparse matrix.

◆ is_dense_A_constructed()

bool is_dense_A_constructed ( ) const

Returns true iff this constraint already has a dense representation, i.e, if GetDenseA() will be cheap.

◆ operator=() [1/2]

LinearConstraint & operator= ( const LinearConstraint & )
delete

◆ operator=() [2/2]

LinearConstraint & operator= ( LinearConstraint && )
delete

◆ RemoveTinyCoefficient()

void RemoveTinyCoefficient ( double tol)

Sets A(i, j) to zero if abs(A(i, j)) <= tol.

Oftentimes the coefficient A is computed numerically with round-off errors. Such small round-off errors can cause numerical issues for certain optimization solvers. Hence it is recommended to remove the tiny coefficients to achieve numerical robustness.

Parameters
tolThe entries in A with absolute value <= tol will be set to 0.
Note
tol>= 0.

◆ set_bounds()

void set_bounds ( const Eigen::Ref< const Eigen::VectorXd > & new_lb,
const Eigen::Ref< const Eigen::VectorXd > & new_ub )

Set the upper and lower bounds of the constraint.

Parameters
new_lbA num_constraints x 1 vector.
new_ubA num_constraints x 1 vector.
Note
If the users want to expose this method in a sub-class, do using Constraint::set_bounds, as in LinearConstraint.

◆ UpdateCoefficients() [1/2]

void UpdateCoefficients ( const Eigen::Ref< const Eigen::MatrixXd > & new_A,
const Eigen::Ref< const Eigen::VectorXd > & new_lb,
const Eigen::Ref< const Eigen::VectorXd > & new_ub )

Updates the linear term, upper and lower bounds in the linear constraint.

The updated constraint is: new_lb <= new_A * x <= new_ub Note that the size of constraints (number of rows) can change, but the number of variables (number of cols) cannot.

Throws if new_A has any entry which is not finite or if new_A, new_lb, and new_ub don't all have the same number of rows.

Parameters
new_Anew linear term
new_lbnew lower bound
new_ubnew upper bound

◆ UpdateCoefficients() [2/2]

void UpdateCoefficients ( const Eigen::SparseMatrix< double > & new_A,
const Eigen::Ref< const Eigen::VectorXd > & new_lb,
const Eigen::Ref< const Eigen::VectorXd > & new_ub )

Overloads UpdateCoefficients but with a sparse A matrix.

Throws if new_A has any entry which is not finite or if new_A, new_lb, and new_ub don't all have the same number of rows.

◆ UpdateLowerBound()

void UpdateLowerBound ( const Eigen::Ref< const Eigen::VectorXd > & new_lb)

Updates the lower bound.

Note
if the users want to expose this method in a sub-class, do using Constraint::UpdateLowerBound, as in LinearConstraint.

◆ UpdateUpperBound()

void UpdateUpperBound ( const Eigen::Ref< const Eigen::VectorXd > & new_ub)

Updates the upper bound.

Note
if the users want to expose this method in a sub-class, do using Constraint::UpdateUpperBound, as in LinearConstraint.

Member Data Documentation

◆ A_

internal::SparseAndDenseMatrix A_
protected

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