Drake
Drake C++ Documentation
Hydroelastic Contact User Guide

A guide to using hydroelastic contact in practice.

Introduction

There are many ways to model contact between rigid bodies. Drake uses an approach we call “compliant” contact. In compliant contact, nominally rigid bodies are allowed to penetrate slightly, as if the rigid body had a slightly deformable layer, but whose compression has no appreciable effect on the body’s mass properties. The contact force between two deformed bodies is distributed over a contact patch with an uneven pressure distribution over that patch. It is common in robotics to model that as a single point contact or a set of point contacts. Hydroelastic contact instead attempts to approximate the patch and pressure distribution to provide much richer and more realistic contact behavior. For a high-level overview, see this blog post.

Drake implements two models for resolving contact to forces: point contact and hydroelastic contact. See Modeling Compliant Contact for a fuller discussion of the theory and practice of contact models. For notes on implementation status, see Appendix A: Current state of implementation. Also see Appendix B: Examples and Tutorials.

Hydroelastic Quick-start

The proximity default configuration settings of SceneGraph offer a quick-start path to using hydroelastic contact without the need to fully annotate the collision geometries of robot models. (The full annotation process is described in Creating hydroelastic representations of collision geometries.)

While it is unlikely that the homogeneous parameters set by automatic hydroelastic configuration will be sufficient to model diverse sets of collision geometries, it may be a good starting point for some. It allows an incremental approach to adding hydroelastic annotations as needed.

To get very simple and quick hydroelastic configuration, all that is needed is to set the configuration for drake::geometry::SceneGraph:

geometry::SceneGraphConfig scene_graph_config;
scene_graph_config.default_proximity_properties.compliance_type = "compliant";
auto [plant, scene_graph] =
multibody::AddMultibodyPlant(plant_config, scene_graph_config, &builder);

For an example of a trivial conversion of an existing simulation, see the examples/simple_gripper program in the Drake source code. It offers a --default_compliance_type command line option, which permits trying various compliance types.

All of the geometries in contexts created for the scene graph will be annotated with a default set of proximity properties.

These transformations will allow hydroelastic contact to work, but the values of the properties may not be ideal. The default set of properties are controlled by drake::geometry::DefaultProximityProperties. They can be changed for each application.

Having used scene graph configuration proximity defaults to get up and running, it may still be useful to add specific hydroelastic annotations to model files. Any explicit properties in model files (or applied by calling Drake APIs) will take precedence over the default proximity properties for the annotated geometries.

Working with Hydroelastic Contact

It is relatively simple to enable a simulation to use hydroelastic contact. However, using it effectively requires some experience and consideration. This section details the mechanisms and choices involved in enabling hydroelastic contact and the next section helps guide you through some common tips, tricks, and traps.

Using hydroelastic contact requires two things:

Collision geometries for hydroelastic contact can be either "compliant-hydroelastic" with tetrahedral meshes describing an internal pressure field or "rigid-hydroelastic" with triangle surface meshes that are regarded as infinitely stiff. The figure below shows examples of a compliant hydroelastic box and a rigid hydroelastic box.

HydroelasticTutorialCompliantRigidOutsideInside800x669.jpg

The figure below shows a contact surface between a compliant-hydroelastic cylinder and a compliant-hydroelastic sphere. The contact surface is internal to both solids and is defined as the surface where the two pressure fields are equal.

HydroelasticTutorialContactSurfaceCompliantCompliant.png

Pictured below, a rigid-hydroelastic cylindrical spatula handle is grasped by two hydroelastic-compliant ellipsoidal bubble grippers. The contact surface between the spatula handle's rigid-hydroelastic geometry and either gripper is on the surface of the rigid-hydroelastic geometry.

HydroelasticTutorialContactSurfaceRigidCompliantBubble.png

Enabling Hydroelastic contact in your simulation

Because MultibodyPlant is responsible for computing the dynamics of the system (and the contact forces are part of that), the ability to enable/disable the hydroelastic contact model is part of MultibodyPlant’s API: drake::multibody::MultibodyPlant::set_contact_model().

There are three different options:

The default model is kHydroelasticWithFallback.

kPoint is the implementation of the point contact model (see Modeling Compliant Contact).

Models kHydroelastic and kHydroelasticWithFallback will both enable the hydroelastic contact. For forces to be created from hydroelastic contact, geometries need to have hydroelastic representations (see Hydroelastic Quick-start, Creating hydroelastic representations of collision geometries).

kHydroelastic is a strict contact model that will attempt to create a hydroelastic contact surface whenever a geometry with a hydroelastic representation appears to be in contact (based on broad-phase bounding volume culling). With this contact model, the simulator will throw an exception if:

Collisions between two geometries where neither has a hydroelastic representation are simply ignored.

kHydroelasticWithFallback provides “fallback” behavior for when kHydroelastic would throw. When those scenarios are detected, it uses the point contact model between the colliding geometries so that the contact can be accounted for and produce contact forces. As the implementation evolves, more and more contact will be captured with hydroelastic contact and the circumstances in which the point-contact fallback is applied will decrease.

Creating hydroelastic representations of collision geometries

There are three ways to configure hydroelastic representations for collision geometries:

If none of the above are done, no geometry in drake::geometry::SceneGraph has a hydroelastic representation. So, enabling hydroelastic contact in MultibodyPlant, but forgetting to configure the geometries will lead to either simulation crashes or point contact-based forces.

In order for a mesh to be given a hydroelastic representation, it must be assigned certain properties. The exact properties it needs depends on the Shape type and whether it is rigid or compliant. Some properties can be defined, but if they are absent they’ll be provided by MultibodyPlant. First we’ll discuss each of the properties and then discuss how they can be specified.

Properties for hydroelastic contact

Assigning hydroelastic properties to geometries

Properties can be assigned to geometries inside a URDF or SDFormat file using some custom Drake XML tags. Alternatively, the properties can be assigned programmatically.

Assigning hydroelastic properties in file specifications

Drake has introduced a number of custom tags to provide a uniform language to specify hydroelastic properties in both URDF and SDFormat. The tag names are the same but the values are expressed differently (to align with the practices common to URDF and SDFormat). For example, consider a custom tag <drake:foo> that takes a single integer value. In an SDFormat file it would look like:

<drake:foo>17</drake:foo>

But in a URDF file it would look like this:

<drake:foo value=”17”/>

Both URDF and SDFormat files define a <collision> tag. This tag contains the tag for specifying the geometry type and associated properties. The hydroelastic properties can be specified as a child of the <collision> tag. Consider the following SDFormat example:

…
  <collision name="body1_collision">
    <geometry>
      ...
    </geometry>
    <drake:proximity_properties>
      <drake:compliant_hydroelastic/>
      <drake:mesh_resolution_hint>0.1</drake:mesh_resolution_hint>
      <drake:hydroelastic_modulus>5e7</drake:hydroelastic_modulus>
      <drake:hunt_crossley_dissipation>1.25</drake:hunt_crossley_dissipation>
    </drake:proximity_properties>
  </collision>
…

and the following equivalent URDF example:

…
  <collision name="body1_collision">
    <geometry>
      ...
    </geometry>
    <drake:proximity_properties>
      <drake:compliant_hydroelastic/>
      <drake:mesh_resolution_hint value="0.1"/>
      <drake:hydroelastic_modulus value="5e7/>
      <drake:hunt_crossley_dissipation value="1.25/>
    </drake:proximity_properties>
  </collision>
…

For a body, we’ve defined a collision geometry called “body1_collision”. Inside the <collision> tag (as a sibling to the <geometry> tag), we’ve introduced the Drake-specific <drake:proximity_properties> tag. In it we’ve defined the geometry to be compliant for hydroelastic contact and specified its resolution hint, its hydroelastic modulus, and its dissipation.

Let’s look at the specific tags:

Assigning hydroelastic properties in code

Hydroelastic properties can be set to objects programmatically via the following APIs (see their documentation for further details):

Some extra notes:

AddContactMaterial() isn’t hydroelastic contact specific, but does provide a mechanism for setting the friction coefficients that hydroelastic and point contact models both use.

AddRigidHydroelasticProperties() is overloaded. One version accepts a value for resolution hint, one does not. When in doubt which to use, it is harmless to provide a resolution hint value that would be ignored for some geometries, but failing to provide one where necessary will cause the simulation to throw an exception. Note the special case for declaring a compliant half space – it takes the required slab thickness parameter in addition to the hydroelastic modulus value.

Visualizing hydroelastic contact

Start Meldis by:

$ bazel run //tools:meldis -- --open-window &

Run a simulation with hydroelastic contact model; for example,

$ bazel run //examples/hydroelastic/ball_plate:ball_plate_run_dynamics -- \
   --mbp_dt=0.001 --x0=0.10 --z0=0.15 --vz=-7.0 \
   --simulation_time=0.015 --simulator_publish_every_time_step

At the time of this writing, the Meldis view of this example looks like this:

drake-vis-01.png

In the above picture, we see two red force vectors acting at the centroids of the two contact surfaces and also the two blue moment vectors. One contact surface represents the ball pushing the dinner plate down. The other contact surface represents the rectangular floor pushing the dinner plate up. (Gravity forces are not shown, nor is the contact between the ball and the floor.) Notice that only approximately half of the bottom of the plate makes contact with the floor.

The Scene panel can toggle on/off many different aspects of the visualization using checkboxes, including: which contacts are shown, whether to view the illustration (visual) geometry and/or collision (proximity) geometry and/or the bodies' inertia, as well as sliders for controlling transparency to better view overlapping shapes.

When viewing collisions, note that red arrows indicate a hydroelastic contact, with an associated contact patch. Green arrows indicate point contact, which does not have any contact patch.

Pitfalls/Troubleshooting

Here are various ways that hydroelastic contact may surprise you.

Tips and Tricks

This is a random collection of things we can do to maximize the benefits of the hydroelastic contact model. Some of these tricks accommodate current implementation limitations, and some are to work within the theoretical framework.

Gaming the model

Appendix A: Current state of implementation

This section will be updated as the scope and feature set of hydroelastic contact is advanced. The main crux of this section is to clearly indicate what can and cannot be done with hydroelastic contact.

What can you do with hydroelastic contact?

What can’t you do with hydroelastic contact?

Current dissipation models

Appendix B: Examples and Tutorials

Sources referenced within this documentation