Drake
Drake C++ Documentation
MultibodyPlantConfig Struct Reference

Detailed Description

The set of configurable properties on a MultibodyPlant.

The field names and defaults here match MultibodyPlant's defaults exactly, with the exception of time_step.

#include <drake/multibody/plant/multibody_plant_config.h>

Public Member Functions

template<typename Archive >
void Serialize (Archive *a)
 Passes this object to an Archive. More...
 

Public Attributes

double time_step {0.001}
 Configures the MultibodyPlant::MultibodyPlant() constructor time_step. More...
 
bool use_sampled_output_ports {true}
 Configures the MultibodyPlant::SetUseSampledOutputPorts(). More...
 
double penetration_allowance {0.001}
 Configures the MultibodyPlant::set_penetration_allowance(). More...
 
double stiction_tolerance {0.001}
 Configures the MultibodyPlant::set_stiction_tolerance(). More...
 
std::string contact_model {"hydroelastic_with_fallback"}
 Configures the MultibodyPlant::set_contact_model(). More...
 
std::string discrete_contact_solver {""}
 Configures the MultibodyPlant::set_discrete_contact_solver(). More...
 
std::string discrete_contact_approximation {""}
 Configures the MultibodyPlant::set_discrete_contact_approximation(). More...
 
double sap_near_rigid_threshold {1.0}
 Non-negative dimensionless number typically in the range [0.0, 1.0], though larger values are allowed even if uncommon. More...
 
std::string contact_surface_representation {"polygon"}
 Configures the MultibodyPlant::set_contact_surface_representation(). More...
 
bool adjacent_bodies_collision_filters {true}
 Configures the MultibodyPlant::set_adjacent_bodies_collision_filters(). More...
 

Member Function Documentation

◆ Serialize()

void Serialize ( Archive *  a)

Passes this object to an Archive.

Refer to YAML Serialization for background.

Member Data Documentation

◆ adjacent_bodies_collision_filters

bool adjacent_bodies_collision_filters {true}

◆ contact_model

std::string contact_model {"hydroelastic_with_fallback"}

Configures the MultibodyPlant::set_contact_model().

Refer to drake::multibody::ContactModel for details. Valid strings are:

  • "point"
  • "hydroelastic"
  • "hydroelastic_with_fallback"

◆ contact_surface_representation

std::string contact_surface_representation {"polygon"}

Configures the MultibodyPlant::set_contact_surface_representation().

Refer to drake::geometry::HydroelasticContactRepresentation for details. Valid strings are:

  • "triangle"
  • "polygon"

The default value used here is consistent with the default time_step chosen above; keep this consistent with MultibodyPlant::GetDefaultContactSurfaceRepresentation().

◆ discrete_contact_approximation

std::string discrete_contact_approximation {""}

Configures the MultibodyPlant::set_discrete_contact_approximation().

Refer to drake::multibody::DiscreteContactApproximation for details. Valid strings are:

  • "tamsi"
  • "sap"
  • "similar"
  • "lagged"

Refer to MultibodyPlant::set_discrete_contact_approximation() and the references therein for further details.

Note
If empty, the contact approximation is determined by discrete_contact_solver, see set_discrete_contact_solver(). If both discrete_contact_solver and discrete_contact_approximation are empty, the default model (and solver) is TAMSI.

◆ discrete_contact_solver

std::string discrete_contact_solver {""}

Configures the MultibodyPlant::set_discrete_contact_solver().

Refer to drake::multibody::DiscreteContactSolver for details. Valid strings are:

  • "tamsi", uses the TAMSI model approximation.
  • "sap" , uses the SAP model approximation.
Note
If empty, the contact solver is determined by discrete_contact_approximation, see MultibodyPlant::set_discrete_contact_approximation(). If both discrete_contact_solver and discrete_contact_approximation are empty, the default model (and solver) is TAMSI.
Warning
discrete_contact_solver is deprecated. Use discrete_contact_approximation to set the contact model approximation. The underlying solver will be inferred automatically. The deprecated code will be removed from Drake on or after 2024-04-01.

◆ penetration_allowance

double penetration_allowance {0.001}

◆ sap_near_rigid_threshold

double sap_near_rigid_threshold {1.0}

Non-negative dimensionless number typically in the range [0.0, 1.0], though larger values are allowed even if uncommon.

This parameter controls the "near rigid" regime of the SAP solver, β in section V.B of [Castro et al., 2021]. It essentially controls a threshold value for the maximum amount of stiffness SAP can handle robustly. Beyond this value, stiffness saturates as explained in [Castro et al., 2021]. A value of 1.0 is a conservative choice to avoid numerical ill-conditioning. However, this might introduce artificial softening of the contact constraints. If this is your case try:

  1. Set this parameter to zero.
  2. For difficult problems (hundreds of contacts for instance), you might need to use a low value if the solver fails to converge. For instance, set values in the range (1e-3, 1e-2).

◆ stiction_tolerance

double stiction_tolerance {0.001}

◆ time_step

double time_step {0.001}

Configures the MultibodyPlant::MultibodyPlant() constructor time_step.

There is no default value for this within MultibodyPlant itself, so here we choose a nominal value (a discrete system, with a 1ms periodic update) as a reasonably conservative estimate that works in many cases.

◆ use_sampled_output_ports

bool use_sampled_output_ports {true}

Configures the MultibodyPlant::SetUseSampledOutputPorts().

Ignored when the time_step is zero.


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