pydrake.multibody.fem
Bindings for multibody fem.
- class pydrake.multibody.fem.DeformableBodyConfig
DeformableBodyConfig stores the physical parameters for a deformable body. A default constructed configuration approximately represents a hard rubber material (density, elasticity, and poisson’s ratio) without any damping. Damping coefficients are generally difficult to measure and we expect users will typically start with zero damping and tune the values to achieve reasonable dynamics. The config contains the following fields with their corresponding valid ranges: - Young’s modulus: Measures the stiffness of the material, has unit N/m². Must be positive. Default to 1e8. - Poisson’s ratio: Measures the Poisson effect (how much the material expands or contracts in directions perpendicular to the direction of loading) of the material, unitless. Must be greater than -1 and less than 0.5. Default to 0.49.
Mass damping coefficient: Controls the strength of mass damping, has unit
1/s. Must be non-negative. Default to 0. See DampingModel. - Stiffness damping coefficient: Controls the strength of stiffness damping, has unit s. Must be non-negative. Default to 0. See DampingModel. - Mass density: Has unit kg/m³. Must be positive. Default to 1.5e3. - Material model: The constitutive model that describes the stress-strain relationship of the body, see MaterialModel. Default to MaterialModel::kCorotated.
Note
This class is templated; see
DeformableBodyConfig_
for the list of instantiations.- __init__(self: pydrake.multibody.fem.DeformableBodyConfig) None
- mass_damping_coefficient(self: pydrake.multibody.fem.DeformableBodyConfig) float
Returns the mass damping coefficient. See DampingModel.
- mass_density(self: pydrake.multibody.fem.DeformableBodyConfig) float
Returns the mass density, with unit of kg/m³.
- material_model(self: pydrake.multibody.fem.DeformableBodyConfig) pydrake.multibody.fem.MaterialModel
Returns the constitutive model of the material.
- poissons_ratio(self: pydrake.multibody.fem.DeformableBodyConfig) float
Returns the Poisson’s ratio, unitless.
- set_mass_damping_coefficient(self: pydrake.multibody.fem.DeformableBodyConfig, mass_damping_coefficient: float) None
- Precondition:
mass_damping_coefficient >= 0.
- set_mass_density(self: pydrake.multibody.fem.DeformableBodyConfig, mass_density: float) None
- Precondition:
mass_density > 0.
- set_material_model(self: pydrake.multibody.fem.DeformableBodyConfig, material_model: pydrake.multibody.fem.MaterialModel) None
- set_poissons_ratio(self: pydrake.multibody.fem.DeformableBodyConfig, poissons_ratio: float) None
- Precondition:
-1 < poissons_ratio < 0.5.
- set_stiffness_damping_coefficient(self: pydrake.multibody.fem.DeformableBodyConfig, stiffness_damping_coefficient: float) None
- Precondition:
stiffness_damping_coefficient >= 0.
- set_youngs_modulus(self: pydrake.multibody.fem.DeformableBodyConfig, youngs_modulus: float) None
- Precondition:
youngs_modulus > 0.
- stiffness_damping_coefficient(self: pydrake.multibody.fem.DeformableBodyConfig) float
Returns the stiffness damping coefficient. See DampingModel.
- youngs_modulus(self: pydrake.multibody.fem.DeformableBodyConfig) float
Returns the Young’s modulus, with unit of N/m².
- template pydrake.multibody.fem.DeformableBodyConfig_
Instantiations:
DeformableBodyConfig_[float]
,DeformableBodyConfig_[AutoDiffXd]
- class pydrake.multibody.fem.DeformableBodyConfig_[AutoDiffXd]
DeformableBodyConfig stores the physical parameters for a deformable body. A default constructed configuration approximately represents a hard rubber material (density, elasticity, and poisson’s ratio) without any damping. Damping coefficients are generally difficult to measure and we expect users will typically start with zero damping and tune the values to achieve reasonable dynamics. The config contains the following fields with their corresponding valid ranges: - Young’s modulus: Measures the stiffness of the material, has unit N/m². Must be positive. Default to 1e8. - Poisson’s ratio: Measures the Poisson effect (how much the material expands or contracts in directions perpendicular to the direction of loading) of the material, unitless. Must be greater than -1 and less than 0.5. Default to 0.49.
Mass damping coefficient: Controls the strength of mass damping, has unit
1/s. Must be non-negative. Default to 0. See DampingModel. - Stiffness damping coefficient: Controls the strength of stiffness damping, has unit s. Must be non-negative. Default to 0. See DampingModel. - Mass density: Has unit kg/m³. Must be positive. Default to 1.5e3. - Material model: The constitutive model that describes the stress-strain relationship of the body, see MaterialModel. Default to MaterialModel::kCorotated.
- __init__(self: pydrake.multibody.fem.DeformableBodyConfig_[AutoDiffXd]) None
- mass_damping_coefficient(self: pydrake.multibody.fem.DeformableBodyConfig_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd
Returns the mass damping coefficient. See DampingModel.
- mass_density(self: pydrake.multibody.fem.DeformableBodyConfig_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd
Returns the mass density, with unit of kg/m³.
- material_model(self: pydrake.multibody.fem.DeformableBodyConfig_[AutoDiffXd]) pydrake.multibody.fem.MaterialModel
Returns the constitutive model of the material.
- poissons_ratio(self: pydrake.multibody.fem.DeformableBodyConfig_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd
Returns the Poisson’s ratio, unitless.
- set_mass_damping_coefficient(self: pydrake.multibody.fem.DeformableBodyConfig_[AutoDiffXd], mass_damping_coefficient: pydrake.autodiffutils.AutoDiffXd) None
- Precondition:
mass_damping_coefficient >= 0.
- set_mass_density(self: pydrake.multibody.fem.DeformableBodyConfig_[AutoDiffXd], mass_density: pydrake.autodiffutils.AutoDiffXd) None
- Precondition:
mass_density > 0.
- set_material_model(self: pydrake.multibody.fem.DeformableBodyConfig_[AutoDiffXd], material_model: pydrake.multibody.fem.MaterialModel) None
- set_poissons_ratio(self: pydrake.multibody.fem.DeformableBodyConfig_[AutoDiffXd], poissons_ratio: pydrake.autodiffutils.AutoDiffXd) None
- Precondition:
-1 < poissons_ratio < 0.5.
- set_stiffness_damping_coefficient(self: pydrake.multibody.fem.DeformableBodyConfig_[AutoDiffXd], stiffness_damping_coefficient: pydrake.autodiffutils.AutoDiffXd) None
- Precondition:
stiffness_damping_coefficient >= 0.
- set_youngs_modulus(self: pydrake.multibody.fem.DeformableBodyConfig_[AutoDiffXd], youngs_modulus: pydrake.autodiffutils.AutoDiffXd) None
- Precondition:
youngs_modulus > 0.
- stiffness_damping_coefficient(self: pydrake.multibody.fem.DeformableBodyConfig_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd
Returns the stiffness damping coefficient. See DampingModel.
- youngs_modulus(self: pydrake.multibody.fem.DeformableBodyConfig_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd
Returns the Young’s modulus, with unit of N/m².
- class pydrake.multibody.fem.MaterialModel
Types of material models for the deformable body.
Members:
kLinearCorotated : Linear corotational model as described in [Han et al., 2023]. It
provides a combination of accuracy, robustness, and speed. Recommended in most scenarios. [Han et al., 2023] Han, Xuchen, Joseph Masterjohn, and Alejandro Castro. “A Convex Formulation of Frictional Contact between Rigid and Deformable Bodies.” arXiv preprint arXiv:2303.08912 (2023).
kCorotated : Corotational model. More computationally expensive and less robust
than the linear corotational model. May require smaller time steps. Recommended when capturing large rotation velocity is important.
kLinear : Linear elasticity model (rarely used). Less computationally expensive
than other models but leads to artifacts when large rotational deformations occur.
- __init__(self: pydrake.multibody.fem.MaterialModel, value: int) None
- kCorotated = <MaterialModel.kCorotated: 1>
- kLinear = <MaterialModel.kLinear: 2>
- kLinearCorotated = <MaterialModel.kLinearCorotated: 0>
- property name
- property value