Drake
Drake C++ Documentation
StaticFrictionConeConstraint Class Reference

Detailed Description

Formulates the nonlinear friction cone constraint |fₜ| ≤ μ*fₙ, where fₜ is the tangential contact force, fₙ is the normal contact force, and μ is the friction coefficient.

The mathematical formulation of this constraint is

0 ≤ μ*fᵀn
fᵀ((1+μ²)nnᵀ - I)f ≥ 0

where n is the unit length normal vector. This formulation is equivalent to |fₜ| ≤ μ*fₙ, but the constraint is differentiable everywhere (while |fₜ| ≤ μ*fₙ is not differentiable at fₜ = 0.)

The bound variables for this constraint is x = [q;λ], where q is the generalized position, and λ is the parameterization of the contact wrench.

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

Public Member Functions

 StaticFrictionConeConstraint (const ContactWrenchEvaluator *contact_wrench_evaluator)
 
 ~StaticFrictionConeConstraint () override
 
template<typename T >
void DecomposeX (const Eigen::Ref< const VectorX< T >> &x, VectorX< T > *q, VectorX< T > *lambda) const
 Given the bound variable x, decompose it into the generalized position q, and λ as a parameterization of the contact wrench. More...
 
Does not allow copy, move, or assignment
 StaticFrictionConeConstraint (const StaticFrictionConeConstraint &)=delete
 
StaticFrictionConeConstraintoperator= (const StaticFrictionConeConstraint &)=delete
 
 StaticFrictionConeConstraint (StaticFrictionConeConstraint &&)=delete
 
StaticFrictionConeConstraintoperator= (StaticFrictionConeConstraint &&)=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...
 
 EvaluatorBase (const EvaluatorBase &)=delete
 
EvaluatorBaseoperator= (const EvaluatorBase &)=delete
 
 EvaluatorBase (EvaluatorBase &&)=delete
 
EvaluatorBaseoperator= (EvaluatorBase &&)=delete
 

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)
 

Constructor & Destructor Documentation

◆ StaticFrictionConeConstraint() [1/3]

◆ StaticFrictionConeConstraint() [2/3]

◆ StaticFrictionConeConstraint() [3/3]

StaticFrictionConeConstraint ( const ContactWrenchEvaluator contact_wrench_evaluator)
Parameters
contact_wrench_evaluator.The evaluator takes in the generalized position q, and a parameterization of the contact wrench λ, and evaluates the contact wrench from body A to body B applied at the witness point of geometry B expressed in the world frame, i.e., computes the contact wrench F_Cb_W at the witness point p_WCb_W (see SignedDistancePair for the definition of witness point), and F_Ca_W = -F_Cb_W (assuming Ca and Cb are at the same spatial location).
Note
although contact_wrench_evaluator computes both the contact force and torque in the wrench, we only constrain the contact force to be within the friction cone, and leave the torque unconstrained.

◆ ~StaticFrictionConeConstraint()

Member Function Documentation

◆ DecomposeX()

void DecomposeX ( const Eigen::Ref< const VectorX< T >> &  x,
VectorX< T > *  q,
VectorX< T > *  lambda 
) const

Given the bound variable x, decompose it into the generalized position q, and λ as a parameterization of the contact wrench.

x = [q; λ].

◆ operator=() [1/2]

◆ operator=() [2/2]


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