Skip to content

Commit

Permalink
Updates and documents MultibodyPlant's default proximity values. (#21463
Browse files Browse the repository at this point in the history
)

This PR updates the default value of proximity properties used by MbP.
The idea is that a user can create a model without specifying any contact parameters and run a first simulation with a reasonable approximation of rigid contact. For tighter "rigid contact" or furhter compliance, users of course must provide their contact parameters estimations. This workflow and guidelines for estimation are documented in a new module.

Label "release:fix" is related to the fact that these new contact parameters defaults affect the behavior of Drake's simulations.
  • Loading branch information
amcastro-tri authored Dec 5, 2024
1 parent d553155 commit 804b2c6
Show file tree
Hide file tree
Showing 19 changed files with 331 additions and 66 deletions.
1 change: 1 addition & 0 deletions doc/doxygen_cxx/doxygen.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ namespace drake {
<li> @subpage algorithms </li>
<li> @ref drake::examples "Examples" </li>
<li> @subpage technical_notes </li>
<li> @subpage drake_contacts "Contact Modeling in Drake" </li>
</ul>
<p>For more general information, you can also visit the <a
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
#include "drake/common/drake_assert.h"
#include "drake/examples/allegro_hand/allegro_common.h"
#include "drake/examples/allegro_hand/allegro_lcm.h"
#include "drake/geometry/proximity_properties.h"
#include "drake/lcmt_allegro_command.hpp"
#include "drake/lcmt_allegro_status.hpp"
#include "drake/math/rotation_matrix.h"
Expand All @@ -37,12 +38,14 @@ namespace examples {
namespace allegro_hand {
namespace {

using geometry::ProximityProperties;
using math::RigidTransformd;
using math::RollPitchYawd;
using multibody::JointActuator;
using multibody::JointActuatorIndex;
using multibody::ModelInstanceIndex;
using multibody::MultibodyPlant;
using multibody::RigidBody;

DEFINE_double(simulation_time, std::numeric_limits<double>::infinity(),
"Desired duration of the simulation in seconds");
Expand All @@ -64,6 +67,10 @@ DEFINE_double(
DEFINE_double(
pid_frequency, 10.0,
"This frequency determines the time scale of the PID controller.");
DEFINE_double(point_contact_stiffness, 1.0e4,
"Point contact stiffness at the finger tips, in [N/m].");
DEFINE_double(hunt_crossley_dissipation, 1.0,
"Hunt & Crossley dissipation at the finger tips, in [s/m].");

// Modeling the Allegro hand with and without reflected inertia.
// The default command line parameters are set to model an Allegro hand that
Expand All @@ -86,6 +93,8 @@ void DoMain() {

auto [plant, scene_graph] = multibody::AddMultibodyPlantSceneGraph(
&builder, FLAGS_mbp_discrete_update_period);
plant.set_discrete_contact_approximation(
multibody::DiscreteContactApproximation::kLagged);

std::string hand_model_url;
if (FLAGS_use_right_hand) {
Expand All @@ -106,11 +115,31 @@ void DoMain() {

// Weld the hand to the world frame
const auto& joint_hand_root = plant.GetBodyByName("hand_root");
plant.AddJoint<multibody::WeldJoint>("weld_hand", plant.world_body(),
std::nullopt,
joint_hand_root,
std::nullopt,
RigidTransformd::Identity());
plant.AddJoint<multibody::WeldJoint>(
"weld_hand", plant.world_body(), std::nullopt, joint_hand_root,
std::nullopt, RigidTransformd::Identity());

// Make the fingers compliant, since they are made out of rubber.
std::vector<std::string> finger_links = {"link_3", "link_7", "link_11",
"link_15"};
for (auto& name : finger_links) {
const RigidBody<double>& body = plant.GetBodyByName(name);
const geometry::FrameId frame_id =
plant.GetBodyFrameIdOrThrow(body.index());
for (auto geometry_id : scene_graph.model_inspector().GetGeometries(
frame_id, geometry::Role::kProximity)) {
const ProximityProperties* old_props =
scene_graph.model_inspector().GetProximityProperties(geometry_id);
DRAKE_DEMAND(old_props != nullptr);

ProximityProperties new_props(*old_props);
geometry::AddContactMaterial(FLAGS_hunt_crossley_dissipation,
FLAGS_point_contact_stiffness, {},
&new_props);
scene_graph.AssignRole(*plant.get_source_id(), geometry_id, new_props,
geometry::RoleAssign::kReplace);
}
}

// Model gear ratio and rotor inertia at each finger. In order to model the
// effect of reflected inertia, we need to have the gear ratio and rotor
Expand Down Expand Up @@ -173,8 +202,7 @@ void DoMain() {
}

if (!FLAGS_add_gravity) {
plant.mutable_gravity_field().set_gravity_vector(
Eigen::Vector3d::Zero());
plant.mutable_gravity_field().set_gravity_vector(Eigen::Vector3d::Zero());
}

// Finished building the plant
Expand All @@ -198,8 +226,9 @@ void DoMain() {
MatrixX<double> Sx, Sy;
GetControlPortMapping(plant, &Sx, &Sy);
SetPositionControlledGains(FLAGS_pid_frequency, Ieff, &kp, &ki, &kd);
auto& hand_controller = *builder.AddSystem<
systems::controllers::PidController>(Sx, Sy, kp, ki, kd);
auto& hand_controller =
*builder.AddSystem<systems::controllers::PidController>(Sx, Sy, kp, ki,
kd);
builder.Connect(plant.get_state_output_port(),
hand_controller.get_input_port_estimated_state());
builder.Connect(hand_controller.get_output_port_control(),
Expand Down Expand Up @@ -264,9 +293,8 @@ void DoMain() {
const multibody::RigidBody<double>& mug = plant.GetBodyByName("simple_mug");
const Eigen::Vector3d& p_WHand =
plant.EvalBodyPoseInWorld(plant_context, hand).translation();
RigidTransformd X_WM(
RollPitchYawd(M_PI / 2, 0, 0),
p_WHand + Eigen::Vector3d(0.095, 0.062, 0.095));
RigidTransformd X_WM(RollPitchYawd(M_PI / 2, 0, 0),
p_WHand + Eigen::Vector3d(0.095, 0.062, 0.095));
plant.SetFreeBodyPose(&plant_context, mug, X_WM);

// set the initial command for the hand
Expand Down
37 changes: 30 additions & 7 deletions geometry/scene_graph_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -111,14 +111,25 @@ struct DefaultProximityProperties {
/** @see dynamic_friction. */
std::optional<double> static_friction{0.5};

/** Controls energy damping from contact, for contact models *other than*
multibody::DiscreteContactApproximation::kSap. Units are seconds per
meter. */
std::optional<double> hunt_crossley_dissipation;
/** Controls energy dissipation from contact, for contact approximations
*other than* multibody::DiscreteContactApproximation::kSap. Units are seconds
per meter.
If a non-deformable geometry is missing a value for dissipation,
MultibodyPlant will generate a default value (based on
multibody::MultibodyPlantConfig::penetration_allowance). However, this
behavior will be going away. Therefore, we recommend guaranteeing that every
geometry has a dissipation value either by assigning the property directly to
the geometry or by providing a non-null value here.
Please refer to @ref contact_defaults "Default Contact Parameters" for more
details on Drake's defaults along with guidelines on how to estimate
parameters specific to your model. */
std::optional<double> hunt_crossley_dissipation{50.0};

/** Controls energy damping from contact, *only for*
multibody::DiscreteContactApproximation::kSap. Units are seconds. */
std::optional<double> relaxation_time;
std::optional<double> relaxation_time{0.1};
/// @}

/** @name Point Contact Properties
Expand All @@ -128,8 +139,20 @@ struct DefaultProximityProperties {
@ref point_forces_modeling "Compliant Point Contact Forces",
geometry::AddContactMaterial. */
/// @{
/** A measure of material stiffness, in units of Newtons per meter. */
std::optional<double> point_stiffness;

/** A measure of material stiffness, in units of Newtons per meter.
If a non-deformable geometry is missing a value for stiffness,
MultibodyPlant will generate a default value (based on
multibody::MultibodyPlantConfig::penetration_allowance). However, this
behavior will be going away. Therefore, we recommend guaranteeing that every
geometry has a stiffness value either by assigning the property directly to
the geometry or by providing a non-null value here.
Please refer to @ref contact_defaults "Default Contact Parameters" for more
details on Drake's defaults along with guidelines on how to estimate
parameters specific to your model. */
std::optional<double> point_stiffness{1e6};
/// @}

/** Throws if the values are inconsistent. */
Expand Down
2 changes: 1 addition & 1 deletion geometry/test/scene_graph_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -445,7 +445,7 @@ TEST_F(SceneGraphTest, ApplyConfig) {
// removed, because it is not set in the context's scene graph config, and
// reapplication during AssignRole() does not affect it.
ASSERT_FALSE(scene_graph_.get_config(*context_)
.default_proximity_properties.point_stiffness.has_value());
.default_proximity_properties.slab_thickness.has_value());
edit_props = *query_object().inspector().GetProximityProperties(g_id);
edit_props.RemoveProperty(kHydroGroup, kPointStiffness);
scene_graph_.AssignRole(context_.get(), s_id, g_id, edit_props,
Expand Down
1 change: 1 addition & 0 deletions multibody/plant/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -1011,6 +1011,7 @@ drake_cc_googletest(
drake_cc_googletest(
name = "deformable_integration_test",
deps = [
":multibody_plant_config_functions",
":multibody_plant_core",
"//common/test_utilities:eigen_matrix_compare",
"//geometry:drake_visualizer",
Expand Down
192 changes: 192 additions & 0 deletions multibody/plant/contact_defaults_doxygen.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,192 @@
/** @file
Doxygen-only documentation for @ref drake_contacts. */

// clang-format off (to preserve link to images)

/** @addtogroup contact_defaults Default Contact Parameters
@brief <a><!-- no brief line please --></a>
In Drake, @ref why_rigid "contacts are modeled as compliant". While some may
view the absence of rigid contact modeling as a limitation, it's essential to
understand that rigid contact is itself an approximation; real physical objects
are not truly rigid but simply very stiff. Compliant contact offers an excellent
approximation of rigid contact while often providing better numerical stability
@ref Castro2023 "[Castro et al., 2023]".
Although our solvers can handle stiffness values far exceeding those of real
materials @ref Castro2023 "[Castro et al., 2023]", excessively high stiffness
can lead to numerical ill-conditioning, degraded performance, or even solver
failure. This underscores the importance of carefully selecting contact
parameters—particularly stiffness—to balance robustness and accuracy in
simulations.
To address this, Drake provides default contact parameters specifically designed
to approximate rigid contact while maintaining numerical stability. Below, we
summarize the key parameters most relevant to stiffness and numerical
performance:
|Property [units] | Units | Default value |
|:---------------------------------|:------:|:-------------:|
|Point stiffness | N/m | @ref drake::geometry::DefaultProximityProperties::point_stiffness "Defined here" |
|Hydroelastic modulus | Pa | @ref drake::geometry::DefaultProximityProperties::hydroelastic_modulus "Defined here" |
|Hunt & Crossley dissipation | s/m | @ref drake::geometry::DefaultProximityProperties::hunt_crossley_dissipation "Defined here" |
|Friction | - | @ref drake::geometry::DefaultProximityProperties::dynamic_friction "Defined here" |
|Stiction tolerance | m/s | @ref drake::multibody::MultibodyPlantConfig::stiction_tolerance "Defined here" |
|Marginᵃ | m | @ref drake::geometry::DefaultProximityProperties::margin "Defined here" |
ᵃ Margin has no default yet, this is the recommended value. Refer to
@ref margin_how_much for details.
Users can change these defaults in
drake::geometry::SceneGraphConfig::default_proximity_properties, with the
exception being the stiction tolerance, defined in
drake::multibody::MultibodyPlantConfig.
<h3>Margin</h3>
Though margin and stiction tolerance are not physical parameters, we include
them here since its a set of parameters users should be aware of. For most cases
users will not need to change them. Refer to
@ref hydro_margin for a thorough discussion of margin and to
@ref margin_how_much for a discussion on estimation and recommended values.
<h3>Stiction tolerance</h3>
The stiction tolerance parameterizes our model of regularized friction, see
@ref Castro2023 "[Castro et al., 2023]" for details. While a smaller value
produces a tighter approximation of stiction, it can lead to numerical stiffness
and ill conditioning. The recommended default works for most robotics
applications including the modeling of challenging manipulation tasks, without
sacrificing performance.
<h3>Friction</h3>
We like to think that friction coefficients can generally be categorized into
three ranges: less than 0.2 for slippery surfaces, 0.2 - 0.4 for moderately
smooth surfaces, and greater than 0.5 for rough surfaces. While there is no
theoretical upper limit to the friction coefficient, we'll rarely need a value
larger than 1.0, a good estimate to model very rough or rubber-like surfaces. We
summarize our guideline as follows:
1. <b>\< 0.2</b> for slippery surfaces,
2. <b>0.2-0.4</b> for medium-smooth surfaces,
3. <b>\>0.5</b> for rough surfaces.
<h3>Contact dissipation</h3>
The Hunt & Crossley dissipation parameter is theoretically linked to energy
dissipation during impact and the coefficient of restitution,
@ref HuntCrossley1975 "[Hunt and Crossley 1975]". Practically, we estimate this
parameter using a simple guideline: the inverse of the dissipation parameter, d,
is the maximum bounce speed after contact. For instance, to limit the bounce
speed to 0.1 m/s, set d = 10 s/m.
In robotics, bouncing is often undesirable, and hardware typically favors
inelastic contact. While purely inelastic contact requires d = ∞, values around
40 - 50 s/m effectively approximate this behavior in most applications.
@section Proposed Modeling Workflow
When authoring a new model, this is the workflow we encourage:
1. Author a first pass of your model without specifying contact parameters.
Drake will default to parameters in drake::geometry::SceneGraphConfig.
2. Simulate your model and verify the behavior. For many cases, this will be
enough (e.g. manipulands, anchored bodies, robots, etc.)
3. Adjust model-specific parameters. For instance, rubber pads in a gripper or
robotic feet are better modeled using lower contact stiffnesses. A good way
to estimate stiffness is from known values of deformation (penetration) for a
given force (say weight or gripper effort limit).
4. Friction coefficients might need to be adjusted for modeling smoother
surfaces
5. Iterate between 2 and 4 to better match your application.
For completeness, the next section shows how default contact parameters are
estimated. These notes might be useful for the customized parameter
estimations in your models.
@section contact_defaults_estimating Estimating Contact Stiffness
This section shows how we can estimate stiffness. These guidelines are used to
provide Drake's default values above, but you can also use them to estimate
custom values for your application.
Experience shows that for very stiff objects, increasing material stiffness
beyond a certain large value results in negligible changes in behavior. For
example, when modeling a household object like a mug, the stiffness of diamond,
steel, or wood often yields indistinguishable results for most applications.
However, extremely high stiffness values can cause numerical issues such as
ill-conditioning, poor performance, or even solver failure. As a result,
selecting stiffness to approximate rigid objects involves balancing model
accuracy with numerical stability.
Drake’s default material stiffness values are chosen to provide a practical
approximation of rigid contact. Rigidity is measured based on an acceptable
level of interpenetration, with reasonable bounds set to balance precision and
performance. For instance, there is no benefit in limiting interpenetration to
atomic scales, as it exceeds practical measurement capabilities and
significantly impacts solver performance.
We consider both @ref compliant_point_contact "compliant point contact" and
@ref hydro_contact "hydroelastic contact". For these estimates, we consider a
half-space in contact with a sphere of radius R and water's density, and a
cylinder of radius R and length 4/3⋅R so that it has the same mass as the
sphere.
Algebraic formulas for the contact force and volume in these configurations is
given below:
| Geometry | Volume V | Point Contact | Hydroelastic Contact
|:-----------|:----------------:|:- ------------:|:----------------------
| Cylinder | V = 4/3⋅π⋅R³ | fₙ = k⋅x | fₙ=π⋅E⋅R⋅x
| Sphere | V = 4/3⋅π⋅R³ | fₙ = k⋅x | fₙ=π⋅E⋅x²
The volume (and mass) of these objects is the same since the length of the
cylinder is 4/3⋅R. For the point contact model, the contact force is independent
of contact area and it is always linear with penetration depth x. For
hydroelastic contact, the area of the contact patch is considered and thus the
force is linear with penetration for the cylinder (constant area at small
penetrations) and quadratic for the sphere, refer to the section on @ref
hydro_params_formulas "analytical formulas for hydroelastic" for derivations and
details.
Therefore, for these objects in contact with a flat surface, the expected amount
of penetration under the influence of their own weight is:
| Geometry | Point Contact | Hydroelastic Contact
|:-----------|:----------------------:|:------------------------
| Cylinder | x = 4/3⋅π⋅ρ⋅g/k⋅R³ | x = (4/3⋅ρ⋅g/E) ⋅ R²
| Sphere | x = 4/3⋅π⋅ρ⋅g/k⋅R³ | x = (4/3⋅ρ⋅g/E)¹⸍²⋅R³⸍²
where g is the acceleration of gravity.
As examples, we consider an object of radius 0.05 m, a typical household object
of about half a kilogram, and an object of radius 0.30 m, that with the density
of water, has about 110 kilograms (the mass of a typical humanoid robot).
For point contact, the table below shows the amount of penetration (in meters)
for point contact stiffness k = 10⁶ N/m (Drake's default) and k = 10⁷ N/m (in
parentheses):
| Geometry | R = 0.05 m | R = 0.3 m
|:-----------|:-------------------:|:---------------------
| Cylinder | 5.1⋅10⁻⁶ (5.1⋅10⁻⁷) | 1.1⋅10⁻³ (1.1⋅10⁻⁴)
| Sphere | 5.1⋅10⁻⁶ (5.1⋅10⁻⁷) | 1.1⋅10⁻³ (1.1⋅10⁻⁴)
For hydroelastic contact, the table below shows the amount of penetration (in
meters) for hydroelastic modulus E = 10⁷ Pa (Drake's default) and E = 10⁸ Pa (in
parentheses):
| Geometry | R = 0.05 m | R = 0.3 m
|:-----------|:--------------------:|:---------------------
| Cylinder | 3.3⋅10⁻⁶ (3.3⋅10⁻⁷) | 1.2⋅10⁻⁴ (1.2⋅10⁻⁵)
| Sphere | 4.0⋅10⁻⁴ (1.3⋅10⁻⁴) | 5.9⋅10⁻³ (1.9⋅10⁻³)
From these numerical values we see that Drake's defaults are chosen so that
penetrations are a few submillimeters for household objects and in the
millimeters range for large mobile robots the size of a humanoid. Stiffer values
can be used, but this set of parameters is a good starting point that
effectively trades off a practical approximation of rigid contact with numerical
stiffness.
*/
Loading

0 comments on commit 804b2c6

Please sign in to comment.