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.ForceDensityFieldBase
The ForceDensityFieldBase class is an abstract base class that represents a force density field affecting deformable bodies in a MultibodyPlant. The force field is described by the member function EvaluateAt() which takes as input a position in the world frame and returns the force density from the force density field at the given location, with unit [N/m³]. To create a concrete ForceDensityFieldBase class, inherit from ForceDensityField instead of directly inheriting from ForceDensityFieldBase.
Note
This class is templated; see
ForceDensityFieldBase_
for the list of instantiations.- __init__(*args, **kwargs)
- Clone(self: pydrake.multibody.fem.ForceDensityFieldBase) pydrake.multibody.fem.ForceDensityFieldBase
- density_type(self: pydrake.multibody.fem.ForceDensityFieldBase) pydrake.multibody.fem.ForceDensityType
- EvaluateAt(self: pydrake.multibody.fem.ForceDensityFieldBase, context: pydrake.systems.framework.Context, p_WQ: numpy.ndarray[numpy.float64[3, 1]]) numpy.ndarray[numpy.float64[3, 1]]
Evaluates the force density [N/m³] with the given
context
of the owning MultibodyPlant and a position in world,p_WQ
.
- template pydrake.multibody.fem.ForceDensityFieldBase_
Instantiations:
ForceDensityFieldBase_[float]
,ForceDensityFieldBase_[AutoDiffXd]
,ForceDensityFieldBase_[Expression]
- class pydrake.multibody.fem.ForceDensityFieldBase_[AutoDiffXd]
The ForceDensityFieldBase class is an abstract base class that represents a force density field affecting deformable bodies in a MultibodyPlant. The force field is described by the member function EvaluateAt() which takes as input a position in the world frame and returns the force density from the force density field at the given location, with unit [N/m³]. To create a concrete ForceDensityFieldBase class, inherit from ForceDensityField instead of directly inheriting from ForceDensityFieldBase.
- __init__(*args, **kwargs)
- Clone(self: pydrake.multibody.fem.ForceDensityFieldBase_[AutoDiffXd]) pydrake.multibody.fem.ForceDensityFieldBase_[AutoDiffXd]
- density_type(self: pydrake.multibody.fem.ForceDensityFieldBase_[AutoDiffXd]) pydrake.multibody.fem.ForceDensityType
- EvaluateAt(self: pydrake.multibody.fem.ForceDensityFieldBase_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], p_WQ: numpy.ndarray[object[3, 1]]) numpy.ndarray[object[3, 1]]
Evaluates the force density [N/m³] with the given
context
of the owning MultibodyPlant and a position in world,p_WQ
.
- class pydrake.multibody.fem.ForceDensityFieldBase_[Expression]
The ForceDensityFieldBase class is an abstract base class that represents a force density field affecting deformable bodies in a MultibodyPlant. The force field is described by the member function EvaluateAt() which takes as input a position in the world frame and returns the force density from the force density field at the given location, with unit [N/m³]. To create a concrete ForceDensityFieldBase class, inherit from ForceDensityField instead of directly inheriting from ForceDensityFieldBase.
- __init__(*args, **kwargs)
- Clone(self: pydrake.multibody.fem.ForceDensityFieldBase_[Expression]) pydrake.multibody.fem.ForceDensityFieldBase_[Expression]
- density_type(self: pydrake.multibody.fem.ForceDensityFieldBase_[Expression]) pydrake.multibody.fem.ForceDensityType
- EvaluateAt(self: pydrake.multibody.fem.ForceDensityFieldBase_[Expression], context: pydrake.systems.framework.Context_[Expression], p_WQ: numpy.ndarray[object[3, 1]]) numpy.ndarray[object[3, 1]]
Evaluates the force density [N/m³] with the given
context
of the owning MultibodyPlant and a position in world,p_WQ
.
- class pydrake.multibody.fem.ForceDensityType
(Advanced) Enum for the type of force density in ForceDensityFieldBase.
Members:
kPerCurrentVolume : ForceDensityFieldBase::EvaluateAt() returns the force per unit of
current (deformed) configuration volume.
kPerReferenceVolume : ForceDensityFieldBase::EvaluateAt() returns the force per unit of
reference configuration volume where the reference undeformed configuration is defined by the input mesh provided by the user.
- __init__(self: pydrake.multibody.fem.ForceDensityType, value: int) None
- kPerCurrentVolume = <ForceDensityType.kPerCurrentVolume: 0>
- kPerReferenceVolume = <ForceDensityType.kPerReferenceVolume: 1>
- property name
- property value
- 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. Recommended when
capturing large rotation velocity is important.
[Stomakhin et al., 2012] Stomakhin, Alexey, et al. “Energetically consistent invertible elasticity.” Proceedings of the 11th ACM SIGGRAPH/Eurographics conference on Computer Animation. 2012.
kNeoHookean : Neohookean model. More computationally expensive. Recommended when
capturing large rotation velocity is important. There are subtle differences in physical behavior between the Corotated model and the Neo-Hookean model. See [Smith et al., 2019; Stomakhin et al., 2012] for details. In practice, we often choose the Neo-Hookean model over the Corotated model simply because it’s computationally more efficient.
[Smith et al., 2019] Smith, Breannan, Fernando De Goes, and Theodore Kim. “Stable Neo-Hookean flesh simulation.” ACM Transactions on Graphics (TOG) 37.2 (2018): 1-15.
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: 3>
- kLinearCorotated = <MaterialModel.kLinearCorotated: 0>
- kNeoHookean = <MaterialModel.kNeoHookean: 2>
- property name
- property value