Drake
Drake C++ Documentation
DefaultProximityProperties Struct Reference

Detailed Description

These properties will be used as defaults when the geometry as added via API calls or parsed from model files doesn't say anything more specific.

See also
Modeling Compliant Contact, Hydroelastic Contact User Guide, Modeling of Dry Friction and subsections therein.

#include <drake/geometry/scene_graph_config.h>

Public Member Functions

template<typename Archive >
void Serialize (Archive *a)
 Passes this object to an Archive. More...
 
void ValidateOrThrow () const
 Throws if the values are inconsistent. More...
 

Public Attributes

Hydroelastic Contact Properties

These properties affect hydroelastic contact only.

For more detail, including limits of the numeric parameters,

See also
geometry::AddRigidHydroelasticProperties, geometry::AddCompliantHydroelasticProperties, geometry::AddCompliantHydroelasticPropertiesForHalfSpace.

For more context,

See also
Properties for hydroelastic contact.
std::string compliance_type {"undefined"}
 There are three valid options for compliance_type: More...
 
std::optional< doublehydroelastic_modulus {1e7}
 A measure of material stiffness, in units of Pascals. More...
 
std::optional< doubleresolution_hint {0.02}
 Controls how finely primitive geometries are tessellated, units of meters. More...
 
std::optional< doubleslab_thickness
 For a halfspace, the thickness of compliant material to model, in units of meters. More...
 
std::optional< doublemargin
 (Advanced) Specifies a thin layer of thickness "margin" (in meters) around each geometry. More...
 
General Contact Properties

These properties affect contact in general.

For more detail, including limits of the numeric parameters,

See also
geometry::AddContactMaterial, multibody::CoulombFriction, mbp_contact_modeling, Modeling Dissipation.
std::optional< doubledynamic_friction {0.5}
 To be valid, either both friction values must be populated, or neither. More...
 
std::optional< doublestatic_friction {0.5}
 
std::optional< doublehunt_crossley_dissipation
 Controls energy damping from contact, for contact models other than multibody::DiscreteContactApproximation::kSap. More...
 
std::optional< doublerelaxation_time
 Controls energy damping from contact, only for multibody::DiscreteContactApproximation::kSap. More...
 
Point Contact Properties

These properties affect point contact only.

For complete descriptions of the numeric parameters, See Compliant Point Contact Forces, geometry::AddContactMaterial.

std::optional< doublepoint_stiffness
 A measure of material stiffness, in units of Newtons per meter. More...
 

Member Function Documentation

◆ Serialize()

void Serialize ( Archive *  a)

Passes this object to an Archive.

Refer to YAML Serialization for background.

◆ ValidateOrThrow()

void ValidateOrThrow ( ) const

Throws if the values are inconsistent.

Member Data Documentation

◆ compliance_type

std::string compliance_type {"undefined"}

There are three valid options for compliance_type:

◆ dynamic_friction

std::optional<double> dynamic_friction {0.5}

To be valid, either both friction values must be populated, or neither.

Friction quantities are unitless.

◆ hunt_crossley_dissipation

std::optional<double> hunt_crossley_dissipation

Controls energy damping from contact, for contact models other than multibody::DiscreteContactApproximation::kSap.

Units are seconds per meter.

◆ hydroelastic_modulus

std::optional<double> hydroelastic_modulus {1e7}

A measure of material stiffness, in units of Pascals.

◆ margin

std::optional<double> margin

(Advanced) Specifies a thin layer of thickness "margin" (in meters) around each geometry.

Two bodies with margins δ₁ and δ₂ are considered for contact resolution whenever their distance is within δ₁ + δ₂. That is, (speculative) contact constraints are added for objects at a distance smaller than δ₁+δ₂.

Refer to Margin for Hydroelastic Contact for further details, including theory, examples, recommended margin values and limitations.

There will only be contact if the two zero level sets intersect. Unless the zero level sets of both geometries overlap, there is no contact and no contact force. However, (speculative) contact constraints will be added allowing our discrete contact solvers to predict if a contact "will" occur at the next time step. This leads to additional time coherence and stability. Analytical studies of stability show that a value of 0.1 mm to 1.0 mm is more than enough for most robotics applications. This is not an "action-at-a-distance" trick, there is no contact when the thin margin layers of two objects overlap. The margin is simply a "cheap" mechanism to avoid significantly more complex and costly strategies such as Continuous Collision Detection.

Note
Inflating the geometries does not appreciably change the domain of contact. In the original mesh, the contact pressure is zero on the mesh's boundary surface. When inflating the meshes, we redefine the pressure field so that its zero level set field is a good approximation to the surface of the original geometry. When visualizing hydroelastic proximity geometry, the rendered geometry will include the inflation.
Currently margin only applies to compliant hydroelastic contact and it does not affect point contact.

◆ point_stiffness

std::optional<double> point_stiffness

A measure of material stiffness, in units of Newtons per meter.

◆ relaxation_time

std::optional<double> relaxation_time

Controls energy damping from contact, only for multibody::DiscreteContactApproximation::kSap.

Units are seconds.

◆ resolution_hint

std::optional<double> resolution_hint {0.02}

Controls how finely primitive geometries are tessellated, units of meters.

While no single value is universally appropriate, this value was selected based on the following idea. We're attempting to make introducing novel manipulands as easy as possible. Considering a simple soup can as a representative manipuland, we've picked a value that would result in a tessellated cylinder with enough faces to be appropriate for contact with a compliant gripper.

◆ slab_thickness

std::optional<double> slab_thickness

For a halfspace, the thickness of compliant material to model, in units of meters.

◆ static_friction

std::optional<double> static_friction {0.5}
See also
dynamic_friction.

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