Drake
Drake C++ Documentation

The behavior of a simulation with contact will depend on three factors:

The three factors are interdependent; specific choices for one factor may require supporting changes in the other factors.

Contact Parameters

Contact modeling in Drake is controlled by a small set of parameters:

  1. Per-geometry coefficients of friction. Refer to the documentation for CoulombFriction for details, which also includes a description for modeling the interaction between two surfaces with different coefficients of friction.
  2. Global parameters controlling the stiffness of normal penalty forces. MultibodyPlant offers a single global parameter, the "penetration allowance", described in detail in section Compliant point contact model.
  3. Global parameter controlling the Stribeck approximation of Coulomb friction, refer to section Continuous Approximation of Coulomb Friction for details. set_stiction_tolerance() provides additional information and guidelines on how to set this parameter.
Note
When modeling the multibody system as discrete (refer to the Choice of Time Advancement Strategy section), only the dynamic coefficient of friction is used while the static coefficient of friction is ignored.

Choice of Time Advancement Strategy

MultibodyPlant offers two different modalities to model mechanical systems in time. These are:

  1. As a discrete system with periodic updates (the preferred method for robustness and speed).
  2. As a continuous system.

In this section we'll only provide a very limited distinction between a continuous and a discrete system. A complete discussion of the subject, including the modeling of hybrid systems is beyond the scope of this section and thus the interested is referred to the documentation for Simulator.

Discrete MultibodyPlant

Currently, this is the preferred modality given its speed and robustness. In this modality, the system is updated through periodic updates of length time_step. This can essentially be seen as a time-stepping strategy with a fixed time_step. The value of time_step is provided at construction of the MultibodyPlant. In Drake we use a custom semi-implicit Euler scheme, TAMSI, for multibody systems with regularized friction. Details for this solver are provided in the documentation for TamsiSolver and in [Castro et al., 2019].

[Castro et al., 2019] Castro, A.M, Qu, A., Kuppuswamy, N., Alspach, A., Sherman, M.A., 2019. A Transition-Aware Method for the Simulation of Compliant Contact with Regularized Friction. arXiv:1909.05700 [cs.RO].

Note
For better numerical stability, the discrete model assumes both static and kinetic coefficients of friction to be equal, the static coefficient of friction is ignored.

Continuous MultibodyPlant

If the time_step defined above is specified to be exactly zero at MultibodyPlant construction, the system is modeled as continuous. What that means is that the system is modeled to follow continuous dynamics of the form ẋ = f(t, x, u), where x is the state of the plant, t is time, and u is the set of externally applied inputs (either actuation or external body forces). In this mode, any of Drake's integrators can be used to advance the system forward in time. The following text outlines the implications of using particular integrators.

Integrators can be broadly categorized as one of:

  1. Implicit/Explicit integrators.
  2. Fixed time step/error controlled integrators.

While fixed time step integrators often provide faster simulations, they can miss slip/stick transitions when the stiction tolerance vₛ of the Stribeck approximation is small (say, smaller than 1e-3 m/s). In addition, they might suffer from stability problems when the penalty forces are made stiff (see set_penetration_allowance()).

Error controlled integrators such as RungeKutta3Integrator offer a stable integration scheme by adapting the time step to satisfy a pre-specified accuracy tolerance. However, this stability comes with the price of slower simulations given that often these integrators need to take very small time steps in order to resolve stiff contact dynamics. In addition, these integrators usually perform additional computations to estimate error bounds used to determine step size.

Implicit integrators have the potential to integrate stiff continuous systems forward in time using larger time steps and therefore reduce computational cost. Thus far, with our ImplicitEulerIntegrator we have not observed this advantage for multibody systems using the Stribeck approximation.

Choosing the Right Collision Geometry

The compliant point contact model only reports a single contact between bodies. More particularly, the contact is characterized by a single point. The point is associated with a characteristic area in the model (see above). This has two implications:

Next topic: Continuous Approximation of Coulomb Friction