Drake
StaticFrictionConeComplementarityNonlinearConstraint Class Reference

Detailed Description

The nonlinear constraints to be imposed for static friction force.

See AddStaticFrictionConeComplementarityConstraint() for more details. The nonlinear constraints are (1) - (4) in AddStaticFrictionConeComplementarityConstraint() The bound variable vector for this constraint is x = [q; λ; α; β]

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

Public Member Functions

 StaticFrictionConeComplementarityNonlinearConstraint (const ContactWrenchEvaluator *contact_wrench_evaluator, double complementarity_tolerance)
 See AddStaticFrictionConeComplementarityConstraint() for details. More...
 
 ~StaticFrictionConeComplementarityNonlinearConstraint () override
 
const symbolic::Variablealpha_var () const
 The slack variable for n_Wᵀ * f_W. More...
 
const symbolic::Variablebeta_var () const
 The slack variable for sdf. More...
 
void UpdateComplementarityTolerance (double complementarity_tolerance)
 
const ContactWrenchEvaluatorcontact_wrench_evaluator () const
 
template<typename T >
void DecomposeX (const Eigen::Ref< const VectorX< T >> &x, VectorX< T > *q, VectorX< T > *lambda, T *alpha, T *beta) const
 
Does not allow copy, move, or assignment
 StaticFrictionConeComplementarityNonlinearConstraint (const StaticFrictionConeComplementarityNonlinearConstraint &)=delete
 
StaticFrictionConeComplementarityNonlinearConstraintoperator= (const StaticFrictionConeComplementarityNonlinearConstraint &)=delete
 
 StaticFrictionConeComplementarityNonlinearConstraint (StaticFrictionConeComplementarityNonlinearConstraint &&)=delete
 
StaticFrictionConeComplementarityNonlinearConstraintoperator= (StaticFrictionConeComplementarityNonlinearConstraint &&)=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...
 
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 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
 

Static Public Member Functions

static solvers::Binding< internal::StaticFrictionConeComplementarityNonlinearConstraintMakeBinding (const ContactWrenchEvaluator *contact_wrench_evaluator, double complementarity_tolerance, const Eigen::Ref< const VectorX< symbolic::Variable >> &q_vars, const Eigen::Ref< const VectorX< symbolic::Variable >> &lambda_vars)
 Create a binding of the constraint, together with the bound variables q, λ, α 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 > &lower_bound, const Eigen::Ref< const Eigen::VectorXd > &upper_bound)
 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...
 
void set_num_outputs (int num_outputs)
 

Constructor & Destructor Documentation

◆ StaticFrictionConeComplementarityNonlinearConstraint() [1/3]

◆ StaticFrictionConeComplementarityNonlinearConstraint() [2/3]

◆ StaticFrictionConeComplementarityNonlinearConstraint() [3/3]

StaticFrictionConeComplementarityNonlinearConstraint ( const ContactWrenchEvaluator contact_wrench_evaluator,
double  complementarity_tolerance 
)

◆ ~StaticFrictionConeComplementarityNonlinearConstraint()

Member Function Documentation

◆ alpha_var()

const symbolic::Variable& alpha_var ( ) const

The slack variable for n_Wᵀ * f_W.

See AddStaticFrictionConeComplementarityConstraint().

◆ beta_var()

const symbolic::Variable& beta_var ( ) const

The slack variable for sdf.

See AddStaticFrictionConeComplementarityConstraint().

◆ contact_wrench_evaluator()

const ContactWrenchEvaluator& contact_wrench_evaluator ( ) const

◆ DecomposeX()

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

◆ MakeBinding()

solvers::Binding< internal::StaticFrictionConeComplementarityNonlinearConstraint > MakeBinding ( const ContactWrenchEvaluator contact_wrench_evaluator,
double  complementarity_tolerance,
const Eigen::Ref< const VectorX< symbolic::Variable >> &  q_vars,
const Eigen::Ref< const VectorX< symbolic::Variable >> &  lambda_vars 
)
static

Create a binding of the constraint, together with the bound variables q, λ, α and β.

See AddStaticFrictionConeComplementarityConstraint() for more details.

◆ operator=() [1/2]

◆ operator=() [2/2]

◆ UpdateComplementarityTolerance()

void UpdateComplementarityTolerance ( double  complementarity_tolerance)

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