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

Detailed Description

Implements a constraint of the form \( Ax = b \).

#include <drake/solvers/constraint.h>

Public Member Functions

 LinearEqualityConstraint (const Eigen::Ref< const Eigen::MatrixXd > &Aeq, const Eigen::Ref< const Eigen::VectorXd > &beq)
 Constructs the linear equality constraint Aeq * x = beq.
 LinearEqualityConstraint (const Eigen::SparseMatrix< double > &Aeq, const Eigen::Ref< const Eigen::VectorXd > &beq)
 Overloads the constructor with a sparse matrix Aeq.
 LinearEqualityConstraint (const Eigen::Ref< const Eigen::RowVectorXd > &a, double beq)
 Constructs the linear equality constraint a.dot(x) = beq.
void UpdateCoefficients (const Eigen::Ref< const Eigen::MatrixXd > &Aeq, const Eigen::Ref< const Eigen::VectorXd > &beq)
void UpdateCoefficients (const Eigen::SparseMatrix< double > &Aeq, const Eigen::Ref< const Eigen::VectorXd > &beq)
 Overloads UpdateCoefficients but with a sparse A matrix.
Does not allow copy, move, or assignment
 LinearEqualityConstraint (const LinearEqualityConstraint &)=delete
LinearEqualityConstraintoperator= (const LinearEqualityConstraint &)=delete
 LinearEqualityConstraint (LinearEqualityConstraint &&)=delete
LinearEqualityConstraintoperator= (LinearEqualityConstraint &&)=delete
Public Member Functions inherited from LinearConstraint
 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.
 LinearConstraint (const LinearConstraint &)=delete
LinearConstraintoperator= (const LinearConstraint &)=delete
 LinearConstraint (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

Additional Inherited Members

Protected Member Functions inherited from LinearConstraint
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::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 inherited from LinearConstraint
internal::SparseAndDenseMatrix A_

Constructor & Destructor Documentation

◆ LinearEqualityConstraint() [1/5]

◆ LinearEqualityConstraint() [2/5]

◆ LinearEqualityConstraint() [3/5]

LinearEqualityConstraint ( const Eigen::Ref< const Eigen::MatrixXd > & Aeq,
const Eigen::Ref< const Eigen::VectorXd > & beq )

Constructs the linear equality constraint Aeq * x = beq.

Throws is any entry in Aeq or beq is not finite.

◆ LinearEqualityConstraint() [4/5]

LinearEqualityConstraint ( const Eigen::SparseMatrix< double > & Aeq,
const Eigen::Ref< const Eigen::VectorXd > & beq )

Overloads the constructor with a sparse matrix Aeq.

◆ LinearEqualityConstraint() [5/5]

LinearEqualityConstraint ( const Eigen::Ref< const Eigen::RowVectorXd > & a,
double beq )

Constructs the linear equality constraint a.dot(x) = beq.

Member Function Documentation

◆ operator=() [1/2]

LinearEqualityConstraint & operator= ( const LinearEqualityConstraint & )
delete

◆ operator=() [2/2]

◆ UpdateCoefficients() [1/2]

void UpdateCoefficients ( const Eigen::Ref< const Eigen::MatrixXd > & Aeq,
const Eigen::Ref< const Eigen::VectorXd > & beq )

◆ UpdateCoefficients() [2/2]

void UpdateCoefficients ( const Eigen::SparseMatrix< double > & Aeq,
const Eigen::Ref< const Eigen::VectorXd > & beq )

Overloads UpdateCoefficients but with a sparse A matrix.

Throws if any entry of beq or Aeq is not finite.


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