Drake
Drake C++ Documentation
StaticEquilibriumConstraint Class Referencefinal

Detailed Description

Impose the static equilibrium constraint 0 = τ_g + Bu + ∑J_WBᵀ(q) * Fapp_B_W.

#include <drake/multibody/optimization/static_equilibrium_constraint.h>

Public Member Functions

 ~StaticEquilibriumConstraint () override
 
const std::map< SortedPair< geometry::GeometryId >, GeometryPairContactWrenchEvaluatorBinding > & contact_pair_to_wrench_evaluator () const
 Getter for contact_pair_to_wrench_evaluator, passed in the constructor. More...
 
Does not allow copy, move, or assignment
 StaticEquilibriumConstraint (const StaticEquilibriumConstraint &)=delete
 
StaticEquilibriumConstraintoperator= (const StaticEquilibriumConstraint &)=delete
 
 StaticEquilibriumConstraint (StaticEquilibriumConstraint &&)=delete
 
StaticEquilibriumConstraintoperator= (StaticEquilibriumConstraint &&)=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. More...
 
 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. More...
 
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. More...
 
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. More...
 
 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. More...
 
void Eval (const Eigen::Ref< const AutoDiffVecXd > &x, AutoDiffVecXd *y) const
 Evaluates the expression. More...
 
void Eval (const Eigen::Ref< const VectorX< symbolic::Variable >> &x, VectorX< symbolic::Expression > *y) const
 Evaluates the expression. More...
 
void set_description (const std::string &description)
 Set a human-friendly description for the evaluator. More...
 
const std::string & get_description () const
 Getter for a human-friendly description for the evaluator. More...
 
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. More...
 
std::ostream & Display (std::ostream &os) const
 Formats this evaluator into the given stream, without displaying the decision variables it is bound to. More...
 
std::string ToLatex (const VectorX< symbolic::Variable > &vars, int precision=3) const
 Returns a LaTeX string describing this evaluator. More...
 
int num_vars () const
 Getter for the number of variables, namely the number of rows in x, as used in Eval(x, y). More...
 
int num_outputs () const
 Getter for the number of outputs, namely the number of rows in y, as used in Eval(x, y). More...
 
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) . More...
 
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. More...
 
bool is_thread_safe () const
 Returns whether it is safe to call Eval in parallel. More...
 
 EvaluatorBase (const EvaluatorBase &)=delete
 
EvaluatorBaseoperator= (const EvaluatorBase &)=delete
 
 EvaluatorBase (EvaluatorBase &&)=delete
 
EvaluatorBaseoperator= (EvaluatorBase &&)=delete
 

Static Public Member Functions

static solvers::Binding< StaticEquilibriumConstraintMakeBinding (const MultibodyPlant< AutoDiffXd > *plant, systems::Context< AutoDiffXd > *context, const std::vector< std::pair< std::shared_ptr< ContactWrenchEvaluator >, VectorX< symbolic::Variable >>> &contact_wrench_evaluators_and_lambda, const Eigen::Ref< const VectorX< symbolic::Variable >> &q_vars, const Eigen::Ref< const VectorX< symbolic::Variable >> &u_vars)
 Create a static equilibrium constraint 0 = g(q) + Bu + ∑ᵢ JᵢᵀFᵢ_AB_W(λᵢ) This constraint depends on the variables q, u and λ. More...
 

Additional Inherited Members

- Protected Member Functions inherited from Constraint
void UpdateLowerBound (const Eigen::Ref< const Eigen::VectorXd > &new_lb)
 Updates the lower bound. More...
 
void UpdateUpperBound (const Eigen::Ref< const Eigen::VectorXd > &new_ub)
 Updates the upper bound. More...
 
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. More...
 
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. More...
 
virtual std::ostream & DoDisplay (std::ostream &os, const VectorX< symbolic::Variable > &vars) const
 NVI implementation of Display. More...
 
virtual std::string DoToLatex (const VectorX< symbolic::Variable > &vars, int precision) const
 
void set_num_outputs (int num_outputs)
 
void set_is_thread_safe (bool is_thread_safe)
 

Constructor & Destructor Documentation

◆ StaticEquilibriumConstraint() [1/2]

◆ StaticEquilibriumConstraint() [2/2]

◆ ~StaticEquilibriumConstraint()

Member Function Documentation

◆ contact_pair_to_wrench_evaluator()

const std::map<SortedPair<geometry::GeometryId>, GeometryPairContactWrenchEvaluatorBinding>& contact_pair_to_wrench_evaluator ( ) const

Getter for contact_pair_to_wrench_evaluator, passed in the constructor.

◆ MakeBinding()

static solvers::Binding<StaticEquilibriumConstraint> MakeBinding ( const MultibodyPlant< AutoDiffXd > *  plant,
systems::Context< AutoDiffXd > *  context,
const std::vector< std::pair< std::shared_ptr< ContactWrenchEvaluator >, VectorX< symbolic::Variable >>> &  contact_wrench_evaluators_and_lambda,
const Eigen::Ref< const VectorX< symbolic::Variable >> &  q_vars,
const Eigen::Ref< const VectorX< symbolic::Variable >> &  u_vars 
)
static

Create a static equilibrium constraint 0 = g(q) + Bu + ∑ᵢ JᵢᵀFᵢ_AB_W(λᵢ) This constraint depends on the variables q, u and λ.

Parameters
plantThe plant on which the constraint is imposed.
contextThe context for the subsystem plant.
contact_wrench_evaluators_and_lambdaFor each contact pair, we need to compute the contact wrench applied at the point of contact, expressed in the world frame, namely Fᵢ_AB_W(λᵢ). contact_wrench_evaluators_and_lambda.first is the evaluator for computing this contact wrench from the variables λᵢ. contact_wrench_evaluators_and_lambda.second are the decision variable λᵢ used in computing the contact wrench. Notice the generalized position q is not included in variables contact_wrench_evaluators_and_lambda.second.
q_varsThe decision variables for q (the generalized position).
u_varsThe decision variables for u (the input).
Returns
binding The binding between the static equilibrium constraint and the variables q, u and λ.
Precondition
plant must have been connected to a SceneGraph properly. You could refer to AddMultibodyPlantSceneGraph on how to connect a MultibodyPlant to a SceneGraph.

◆ operator=() [1/2]

◆ operator=() [2/2]


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