(FUTURE) 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.
#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,
For more context,
| |
std::string | compliance_type {"undefined"} |
There are three valid options for compliance_type : More... | |
std::optional< double > | hydroelastic_modulus {1e7} |
A measure of material stiffness, in units of Pascals. More... | |
std::optional< double > | resolution_hint {0.5} |
Controls how finely primitive geometries are tessellated, units of meters. More... | |
std::optional< double > | slab_thickness {10.0} |
For a halfspace, the thickness of compliant material to model, in units of meters. More... | |
General Contact Properties | |
These properties affect contact in general. For more detail, including limits of the numeric parameters, | |
std::optional< double > | dynamic_friction {0.5} |
To be valid, either both friction values must be populated, or neither. More... | |
std::optional< double > | static_friction {0.5} |
std::optional< double > | hunt_crossley_dissipation |
Controls energy damping from contact, for contact models other than multibody::DiscreteContactApproximation::kSap. More... | |
std::optional< double > | relaxation_time |
Controls energy damping from contact, only for multibody::DiscreteContactApproximation::kSap. More... | |
Point Contact Properties | |
These properties point contact only. For complete descriptions of the numeric parameters,
| |
std::optional< double > | point_stiffness |
A measure of material stiffness, in units of Newtons per meter. More... | |
void Serialize | ( | Archive * | a | ) |
Passes this object to an Archive.
Refer to YAML Serialization for background.
void ValidateOrThrow | ( | ) | const |
Throws if the values are inconsistent.
std::string compliance_type {"undefined"} |
There are three valid options for compliance_type
:
std::optional<double> dynamic_friction {0.5} |
To be valid, either both friction values must be populated, or neither.
Friction quantities are unitless.
std::optional<double> hunt_crossley_dissipation |
Controls energy damping from contact, for contact models other than multibody::DiscreteContactApproximation::kSap.
Units are seconds per meter.
std::optional<double> hydroelastic_modulus {1e7} |
A measure of material stiffness, in units of Pascals.
std::optional<double> point_stiffness |
A measure of material stiffness, in units of Newtons per meter.
std::optional<double> relaxation_time |
Controls energy damping from contact, only for multibody::DiscreteContactApproximation::kSap.
Units are seconds.
std::optional<double> resolution_hint {0.5} |
Controls how finely primitive geometries are tessellated, units of meters.
std::optional<double> slab_thickness {10.0} |
For a halfspace, the thickness of compliant material to model, in units of meters.
std::optional<double> static_friction {0.5} |