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... | |
void Serialize | ( | Archive * | a | ) |
Passes this object to an Archive.
Refer to YAML Serialization for background.
bool adjacent_bodies_collision_filters {true} |
Configures the MultibodyPlant::set_adjacent_bodies_collision_filters().
std::string contact_model {"hydroelastic_with_fallback"} |
Configures the MultibodyPlant::set_contact_model().
Refer to drake::multibody::ContactModel for details. Valid strings are:
std::string contact_surface_representation {"polygon"} |
Configures the MultibodyPlant::set_contact_surface_representation().
Refer to drake::geometry::HydroelasticContactRepresentation for details. Valid strings are:
The default value used here is consistent with the default time_step chosen above; keep this consistent with MultibodyPlant::GetDefaultContactSurfaceRepresentation().
std::string discrete_contact_approximation {""} |
Configures the MultibodyPlant::set_discrete_contact_approximation().
Refer to drake::multibody::DiscreteContactApproximation for details. Valid strings are:
Refer to MultibodyPlant::set_discrete_contact_approximation() and the references therein for further details.
std::string discrete_contact_solver {""} |
Configures the MultibodyPlant::set_discrete_contact_solver().
Refer to drake::multibody::DiscreteContactSolver for details. Valid strings are:
double penetration_allowance {0.001} |
Configures the MultibodyPlant::set_penetration_allowance().
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:
double stiction_tolerance {0.001} |
Configures the MultibodyPlant::set_stiction_tolerance().
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.
bool use_sampled_output_ports {true} |
Configures the MultibodyPlant::SetUseSampledOutputPorts().
Ignored when the time_step is zero.