The DeformableBody class represents a single deformable element within a MultibodyPlant.
It encapsulates the mesh, physical properties, and finite-element model required to simulate deformable behavior. It manages:
This class is not meant to be created by end users and it must be created exclusively by DeformableModel through DeformableModel::RegisterDeformableBody.
T | The scalar type, which must be double . |
#include <drake/multibody/tree/deformable_body.h>
Public Member Functions | |
DeformableBodyIndex | index () const |
Returns this element's unique index. More... | |
DeformableBodyId | body_id () const |
Returns the unique body id. More... | |
const std::string & | name () const |
Returns the name of the body. More... | |
ScopedName | scoped_name () const |
Returns scoped name of this body. More... | |
geometry::GeometryId | geometry_id () const |
Returns the geometry id of the deformable geometry used to simulate this deformable body. More... | |
const fem::DeformableBodyConfig< T > & | config () const |
Returns physical parameters of this deformable body. More... | |
int | num_dofs () const |
Returns the number of degrees of freedom (DoFs) of this body. More... | |
const VectorX< double > & | reference_positions () const |
Returns the reference positions of the vertices of the deformable body identified by the given id . More... | |
const fem::FemModel< T > & | fem_model () const |
Returns the FemModel for this deformable body. More... | |
const std::vector< const ForceDensityFieldBase< T > * > & | external_forces () const |
Returns all the external forces acting on this deformable body. More... | |
systems::DiscreteStateIndex | discrete_state_index () const |
Returns the index of the discrete state associated with this deformable body in the MultibodyPlant that owns the body. More... | |
systems::AbstractParameterIndex | is_enabled_parameter_index () const |
Returns the index of the boolean parameter indicating whether this deformable body is enabled. More... | |
systems::CacheIndex | fem_state_cache_index () const |
Returns the cache index for the FemState of this deformable body. More... | |
void | set_parallelism (Parallelism parallelism) |
(Internal use only) Configures the parallelism that this DeformableBody uses when opportunities for parallel computation arises. More... | |
void | SetWallBoundaryCondition (const Vector3< T > &p_WQ, const Vector3< T > &n_W) const |
Sets wall boundary conditions for this deformable body. More... | |
MultibodyConstraintId | AddFixedConstraint (const RigidBody< T > &body_B, const math::RigidTransform< double > &X_BA, const geometry::Shape &shape_G, const math::RigidTransform< double > &X_BG) |
Defines a fixed constraint between this deformable body and a rigid body B. More... | |
bool | has_fixed_constraint () const |
Returns true if this deformable body is under any fixed constraint. More... | |
const std::vector< internal::DeformableRigidFixedConstraintSpec > & | fixed_constraint_specs () const |
(Internal use only) Returns a reference to the fixed constraints registered with this deformable body. More... | |
void | SetPositions (systems::Context< T > *context, const Eigen::Ref< const Matrix3X< T >> &q) const |
Sets the vertex positions of this deformable body in the provided context . More... | |
void | SetVelocities (systems::Context< T > *context, const Eigen::Ref< const Matrix3X< T >> &v) const |
Sets the vertex velocities of this deformable body in the provided context . More... | |
void | SetPositionsAndVelocities (systems::Context< T > *context, const Eigen::Ref< const Matrix3X< T >> &q, const Eigen::Ref< const Matrix3X< T >> &v) const |
Sets the vertex positions and velocities of this deformable body in the provided context . More... | |
Matrix3X< T > | GetPositions (const systems::Context< T > &context) const |
Copies out the matrix of vertex positions for this deformable body in the provided context . More... | |
Matrix3X< T > | GetVelocities (const systems::Context< T > &context) const |
Copies out the matrix of vertex velocities for this deformable body in the provided context . More... | |
Matrix3X< T > | GetPositionsAndVelocities (const systems::Context< T > &context) const |
Copies out the matrix of vertex positions and velocities for this deformable body in the provided context . More... | |
bool | is_enabled (const systems::Context< T > &context) const |
void | Disable (systems::Context< T > *context) const |
Disables this deformable body in the given context. More... | |
void | Enable (systems::Context< T > *context) const |
Enables this deformable body in the given context. More... | |
void | set_default_pose (const math::RigidTransform< double > &X_WD) |
Sets the default pose of the simulated geometry (in its reference configuration) in the world frame W. More... | |
const math::RigidTransform< double > & | get_default_pose () const |
Returns the default pose of the simulated geometry (in its reference configuration) in the world frame W. More... | |
Vector3< T > | CalcCenterOfMassPositionInWorld (const systems::Context< T > &context) const |
Calculates the body's center of mass position in world frame W. More... | |
Vector3< T > | CalcCenterOfMassTranslationalVelocityInWorld (const systems::Context< T > &context) const |
Calculates the body's center of mass translational velocity in world frame W. More... | |
Vector3< T > | CalcEffectiveAngularVelocity (const systems::Context< T > &context) const |
Using an angular momentum analogy, calculates an "effective" angular velocity for this body about its center of mass, measured and expressed in the world frame W. More... | |
Does not allow copy, move, or assignment | |
DeformableBody (const DeformableBody &)=delete | |
DeformableBody & | operator= (const DeformableBody &)=delete |
DeformableBody (DeformableBody &&)=delete | |
DeformableBody & | operator= (DeformableBody &&)=delete |
![]() | |
virtual | ~MultibodyElement () |
ModelInstanceIndex | model_instance () const |
Returns the ModelInstanceIndex of the model instance to which this element belongs. More... | |
template<typename = void> | |
const MultibodyPlant< T > & | GetParentPlant () const |
Returns the MultibodyPlant that owns this MultibodyElement. More... | |
void | DeclareParameters (internal::MultibodyTreeSystem< T > *tree_system) |
Declares MultibodyTreeSystem Parameters at MultibodyTreeSystem::Finalize() time. More... | |
void | SetDefaultParameters (systems::Parameters< T > *parameters) const |
Sets default values of parameters belonging to each MultibodyElement in parameters at a call to MultibodyTreeSystem::SetDefaultParameters(). More... | |
void | DeclareDiscreteState (internal::MultibodyTreeSystem< T > *tree_system) |
Declares MultibodyTreeSystem discrete states. More... | |
void | DeclareCacheEntries (internal::MultibodyTreeSystem< T > *tree_system) |
(Advanced) Declares all cache entries needed by this element. More... | |
bool | is_ephemeral () const |
Returns true if this MultibodyElement was added during Finalize() rather than something a user added. More... | |
void | set_is_ephemeral (bool is_ephemeral) |
(Internal use only) Sets the is_ephemeral flag to the indicated value. More... | |
MultibodyElement (const MultibodyElement &)=delete | |
MultibodyElement & | operator= (const MultibodyElement &)=delete |
MultibodyElement (MultibodyElement &&)=delete | |
MultibodyElement & | operator= (MultibodyElement &&)=delete |
Friends | |
template<typename U > | |
class | DeformableModel |
template<typename U > | |
class | DeformableBody |
Additional Inherited Members | |
![]() | |
MultibodyElement () | |
Default constructor made protected so that sub-classes can still declare their default constructors if they need to. More... | |
MultibodyElement (ModelInstanceIndex model_instance) | |
Constructor which allows specifying a model instance. More... | |
MultibodyElement (ModelInstanceIndex model_instance, int64_t index) | |
Both the model instance and element index are specified. More... | |
template<typename ElementIndexType > | |
ElementIndexType | index_impl () const |
Returns this element's unique index. More... | |
template<typename ElementOrdinalType = int64_t> | |
ElementOrdinalType | ordinal_impl () const |
Returns this element's unique ordinal. More... | |
const internal::MultibodyTree< T > & | get_parent_tree () const |
Returns a constant reference to the parent MultibodyTree that owns this element. More... | |
const internal::MultibodyTreeSystem< T > & | GetParentTreeSystem () const |
Returns a constant reference to the parent MultibodyTreeSystem that owns the parent MultibodyTree that owns this element. More... | |
void | SetTopology (const internal::MultibodyTreeTopology &tree) |
Gives MultibodyElement-derived objects the opportunity to retrieve their topology after MultibodyTree::Finalize() is invoked. More... | |
virtual void | DoSetDefaultParameters (systems::Parameters< T > *) const |
Implementation of the NVI SetDefaultParameters(). More... | |
systems::NumericParameterIndex | DeclareNumericParameter (internal::MultibodyTreeSystem< T > *tree_system, const systems::BasicVector< T > &model_vector) |
To be used by MultibodyElement-derived objects when declaring parameters in their implementation of DoDeclareParameters(). More... | |
systems::AbstractParameterIndex | DeclareAbstractParameter (internal::MultibodyTreeSystem< T > *tree_system, const AbstractValue &model_value) |
To be used by MultibodyElement-derived objects when declaring parameters in their implementation of DoDeclareParameters(). More... | |
systems::DiscreteStateIndex | DeclareDiscreteState (internal::MultibodyTreeSystem< T > *tree_system, const VectorX< T > &model_value) |
To be used by MultibodyElement-derived objects when declaring discrete states in their implementation of DoDeclareDiscreteStates(). More... | |
systems::CacheEntry & | DeclareCacheEntry (internal::MultibodyTreeSystem< T > *tree_system, std::string description, systems::ValueProducer value_producer, std::set< systems::DependencyTicket > prerequisites_of_calc) |
To be used by MultibodyElement-derived objects when declaring cache entries in their implementation of DoDeclareCacheEntries(). More... | |
bool | has_parent_tree () const |
Returns true if this multibody element has a parent tree, otherwise false. More... | |
|
delete |
|
delete |
MultibodyConstraintId AddFixedConstraint | ( | const RigidBody< T > & | body_B, |
const math::RigidTransform< double > & | X_BA, | ||
const geometry::Shape & | shape_G, | ||
const math::RigidTransform< double > & | X_BG | ||
) |
Defines a fixed constraint between this deformable body and a rigid body B.
Such a fixed constraint is modeled as distance holonomic constraints:
p_PᵢQᵢ(q) = 0 for each constrained vertex Pᵢ
where Pᵢ is the i-th vertex of the deformable body (A) under constraint and Qᵢ is a point rigidly affixed to the rigid body B. To specify the constraint, we put the reference mesh M of this body A in B's body frame with the given pose X_BA
and prescribe a shape G with pose X_BG
in B's body frame. All vertices Pᵢ in M that are inside (or on the surface of) G are subject to the fixed constraints with Qᵢ being coincident with Pᵢ when M is in pose X_BA. p_PᵢQᵢ(q) denotes the relative position of point Qᵢ with respect to point Pᵢ as a function of the configuration of the model q. Imposing this constraint forces Pᵢ and Qᵢ to be coincident for each vertex i of the deformable body specified to be under constraint.
[in] | body_B | The rigid body under constraint. |
[in] | X_BA | The pose of this deformable body A's reference mesh in B's body frame. |
[in] | shape_G | The prescribed geometry shape, attached to rigid body B, used to determine which vertices of this deformable body A is under constraint. |
[in] | X_BG | The fixed pose of the geometry frame of the given shape in body B's frame. |
std::exception | unless body_B is registered with the same multibody tree owning this deformable body. |
std::exception | if no constraint is added (i.e. no vertex of the deformable body is inside the given shape with the given poses). |
std::exception | if this element is not associated with a MultibodyPlant. |
DeformableBodyId body_id | ( | ) | const |
Returns the unique body id.
Vector3<T> CalcCenterOfMassPositionInWorld | ( | const systems::Context< T > & | context | ) | const |
Calculates the body's center of mass position in world frame W.
[in] | context | The context associated with the MultibodyPlant that owns this body. |
p_WBcm_W | the body's center of mass position, measured and expressed in the world frame W. |
std::exception | if context does not belong to the MultibodyPlant that owns this body. |
Vector3<T> CalcCenterOfMassTranslationalVelocityInWorld | ( | const systems::Context< T > & | context | ) | const |
Calculates the body's center of mass translational velocity in world frame W.
[in] | context | The context associated with the MultibodyPlant that owns this body. |
v_WScm_W | Scm's translational velocity in frame W, expressed in W, where Scm is the center of mass of this body. |
std::exception | if context does not belong to the MultibodyPlant that owns this body. |
Vector3<T> CalcEffectiveAngularVelocity | ( | const systems::Context< T > & | context | ) | const |
Using an angular momentum analogy, calculates an "effective" angular velocity for this body about its center of mass, measured and expressed in the world frame W.
The effective angular velocity is computed using an angular momentum equation that assumes the body is a rigid body (albeit we know it is deformable).
H_WBcm_W = I_BBcm_W * w_WBcm_W
for which when solved for w_WBcm_W gives
w_WBcm_W = inverse(I_BBcm_W) * H_WBcm_W
where H_WBcm_W is the body's angular momentum about its center of mass Bcm measured and expressed in the world frame W.
[in] | context | The context associated with the MultibodyPlant that owns this body. |
w_WBcm_W | the body's effective angular velocity about Bcm, measured and expressed in the world frame W. |
std::exception | if context does not belong to the MultibodyPlant that owns this body. |
const fem::DeformableBodyConfig<T>& config | ( | ) | const |
Returns physical parameters of this deformable body.
void Disable | ( | systems::Context< T > * | context | ) | const |
Disables this deformable body in the given context.
Disabling a deformable body sets its vertex velocities and accelerations to zero and freezes its vertex positions. A disabled deformable body is not subject to any constraint (e.g. frictional contact constraint or fixed constraint); it does not move under the influence of external forces (e.g. gravity); and it does not necessarily satisfy the prescribed boundary condition (if any). On the flip side, a disabled deformable body does not affect the dynamics of other bodies, even if the collision between the disabled body's geometry and other geometries is not filtered. Effectively, the physics of the deformable body stop being computed. The deformable body can be enabled by calling Enable(). Calling Disable() on a body which is already disabled has no effect.
std::exception | if the passed in context isn't compatible with the MultibodyPlant that owns this body. |
std::exception | if context is null. |
systems::DiscreteStateIndex discrete_state_index | ( | ) | const |
Returns the index of the discrete state associated with this deformable body in the MultibodyPlant that owns the body.
void Enable | ( | systems::Context< T > * | context | ) | const |
Enables this deformable body in the given context.
Calling Enable() on a body which is already enabled has no effect.
std::exception | if the passed in context isn't compatible with the MultibodyPlant that owns this body. |
std::exception | if context is null. |
const std::vector<const ForceDensityFieldBase<T>*>& external_forces | ( | ) | const |
Returns all the external forces acting on this deformable body.
const fem::FemModel<T>& fem_model | ( | ) | const |
Returns the FemModel for this deformable body.
systems::CacheIndex fem_state_cache_index | ( | ) | const |
Returns the cache index for the FemState of this deformable body.
const std::vector<internal::DeformableRigidFixedConstraintSpec>& fixed_constraint_specs | ( | ) | const |
(Internal use only) Returns a reference to the fixed constraints registered with this deformable body.
geometry::GeometryId geometry_id | ( | ) | const |
Returns the geometry id of the deformable geometry used to simulate this deformable body.
const math::RigidTransform<double>& get_default_pose | ( | ) | const |
Returns the default pose of the simulated geometry (in its reference configuration) in the world frame W.
This returns pose last set by set_default_pose(), or the pose of the geometry in the world frame W when the body is registered if set_default_pose() has not been called.
Matrix3X<T> GetPositions | ( | const systems::Context< T > & | context | ) | const |
Copies out the matrix of vertex positions for this deformable body in the provided context
.
[in] | context | The context associated with the MultibodyPlant that owns this body. |
q | A 3×N matrix containing the positions of all vertices of the body. |
std::exception | if context does not belong to the MultibodyPlant that owns this body. |
Matrix3X<T> GetPositionsAndVelocities | ( | const systems::Context< T > & | context | ) | const |
Copies out the matrix of vertex positions and velocities for this deformable body in the provided context
.
The first N columns are the positions and the next N columns are the velocities.
[in] | context | The context associated with the MultibodyPlant that owns this body. |
std::exception | if context does not belong to the MultibodyPlant that owns this body. |
Matrix3X<T> GetVelocities | ( | const systems::Context< T > & | context | ) | const |
Copies out the matrix of vertex velocities for this deformable body in the provided context
.
[in] | context | The context associated with the MultibodyPlant that owns this body. |
v | A 3×N matrix containing the velocities of all vertices of the body. |
std::exception | if context does not belong to the MultibodyPlant that owns this body. |
bool has_fixed_constraint | ( | ) | const |
Returns true if this deformable body is under any fixed constraint.
DeformableBodyIndex index | ( | ) | const |
Returns this element's unique index.
bool is_enabled | ( | const systems::Context< T > & | context | ) | const |
std::exception | if the passed in context isn't compatible with the MultibodyPlant that owns this body. |
systems::AbstractParameterIndex is_enabled_parameter_index | ( | ) | const |
Returns the index of the boolean parameter indicating whether this deformable body is enabled.
const std::string& name | ( | ) | const |
Returns the name of the body.
int num_dofs | ( | ) | const |
Returns the number of degrees of freedom (DoFs) of this body.
|
delete |
|
delete |
Returns the reference positions of the vertices of the deformable body identified by the given id
.
The reference positions are the positions of the vertices of the mesh geometry representing the body at registration time, measured and expressed in the world frame. The reference positions are represented as a VectorX with 3N values where N is the number of vertices. The x-, y-, and z-positions (measured and expressed in the world frame) of the j-th vertex are 3j, 3j + 1, and 3j + 2 in the VectorX.
ScopedName scoped_name | ( | ) | const |
Returns scoped name of this body.
Neither of the two pieces of the name will be empty (the scope name and the element name).
std::exception | if this element is not associated with a MultibodyPlant. |
void set_default_pose | ( | const math::RigidTransform< double > & | X_WD | ) |
Sets the default pose of the simulated geometry (in its reference configuration) in the world frame W.
[in] | X_WD | The default pose of the simulated geometry in the world frame W. |
void set_parallelism | ( | Parallelism | parallelism | ) |
(Internal use only) Configures the parallelism that this
DeformableBody uses when opportunities for parallel computation arises.
void SetPositions | ( | systems::Context< T > * | context, |
const Eigen::Ref< const Matrix3X< T >> & | q | ||
) | const |
Sets the vertex positions of this deformable body in the provided context
.
[in,out] | context | The context associated with the MultibodyPlant that owns this body. |
[in] | q | A 3×N matrix of vertex positions. |
std::exception | if any of the following conditions are met:
|
void SetPositionsAndVelocities | ( | systems::Context< T > * | context, |
const Eigen::Ref< const Matrix3X< T >> & | q, | ||
const Eigen::Ref< const Matrix3X< T >> & | v | ||
) | const |
Sets the vertex positions and velocities of this deformable body in the provided context
.
[in,out] | context | The context associated with the MultibodyPlant that owns this body. |
[in] | q | A 3×N matrix of vertex positions. |
[in] | v | A 3×N matrix of vertex velocities. |
std::exception | if any of the following conditions are met:
|
void SetVelocities | ( | systems::Context< T > * | context, |
const Eigen::Ref< const Matrix3X< T >> & | v | ||
) | const |
Sets the vertex velocities of this deformable body in the provided context
.
[in,out] | context | The context associated with the MultibodyPlant that owns this body. |
[in] | v | A 3×N matrix of vertex velocities. |
std::exception | if any of the following conditions are met:
|
Sets wall boundary conditions for this deformable body.
All vertices of the mesh of the deformable body whose reference positions are inside the prescribed open half space are put under zero displacement boundary conditions. The open half space is defined by a plane with outward normal n_W. A vertex V is considered to be subject to the boundary condition if n̂ ⋅ p_QV < 0 where Q is a point on the plane and n̂ is normalized n_W.
[in] | p_WQ | The position of a point Q on the plane in the world frame. |
[in] | n_W | Outward normal to the half space expressed in the world frame. |
|
friend |
|
friend |