Impose the complementarity constraint on the sliding friction using a Coulomb friction cone model. If the contact is sliding, then the tangential friction force is in the opposite direction to the sliding velocity, and the contact force is at the boundary of the friction cone. If the contact is static, then the contact force is within the friction cone.
We decompose the contact force f into two parts, the static contact force f_static, and the contact force during sliding f_sliding. Namely
f = f_static + f_sliding (1)
In order to enforce the constraint that when the contact is sliding, the static friction force is 0, we impose the complementarity constraint
v_sliding_tangential * f_static_normal = 0 (2)
To enforce that the sliding force is on the boundary of the friction cone, we impose
μ * f_sliding_normal = |f_sliding_tangential| (3)
To enforce that the sliding force is in the opposite direction of the sliding velocity, we impose the following constraint with a slack variable c.
f_sliding_tangential = -c * v_sliding_tangential (4) c ≥ 0 (5)
To enforce that the contact force is in the friction cone, we impose
| f_tangential | ≤ μ f_normal (6)
Depending on whether the contact is explicit or implicit, we add constraint (6) by either calling AddSlidingFrictionComplementarityExplicitContactConstraint(), if the user knows explicitly that the contact occurs, or calling AddSlidingFrictionComplementarityImplicitContactConstraint() if the user doesn't know if the contact has to occur.
#include <utility>
#include <vector>
#include "drake/multibody/optimization/contact_wrench_evaluator.h"
#include "drake/multibody/optimization/static_friction_cone_complementarity_constraint.h"
#include "drake/multibody/optimization/static_friction_cone_constraint.h"
#include "drake/solvers/constraint.h"
#include "drake/solvers/mathematical_program.h"
Namespaces | |
drake | |
drake::multibody | |
Functions | |
std::pair< solvers::Binding< internal::SlidingFrictionComplementarityNonlinearConstraint >, solvers::Binding< StaticFrictionConeConstraint > > | AddSlidingFrictionComplementarityExplicitContactConstraint (const ContactWrenchEvaluator *contact_wrench_evaluator, double complementarity_tolerance, const Eigen::Ref< const VectorX< symbolic::Variable >> &q_vars, const Eigen::Ref< const VectorX< symbolic::Variable >> &v_vars, const Eigen::Ref< const VectorX< symbolic::Variable >> &lambda_vars, solvers::MathematicalProgram *prog) |
For a pair of geometries in explicit contact, adds the sliding friction complementarity constraint explained in sliding_friction_complementarity_constraint to an optimization program. More... | |
std::pair< solvers::Binding< internal::SlidingFrictionComplementarityNonlinearConstraint >, solvers::Binding< internal::StaticFrictionConeComplementarityNonlinearConstraint > > | AddSlidingFrictionComplementarityImplicitContactConstraint (const ContactWrenchEvaluator *contact_wrench_evaluator, double complementarity_tolerance, const Eigen::Ref< const VectorX< symbolic::Variable >> &q_vars, const Eigen::Ref< const VectorX< symbolic::Variable >> &v_vars, const Eigen::Ref< const VectorX< symbolic::Variable >> &lambda_vars, solvers::MathematicalProgram *prog) |
For a pair of geometries in implicit contact (they may or may not be in contact, adds the sliding friction complementarity constraint explained in sliding_friction_complementarity_constraint. More... | |