Drake
Drake C++ Documentation
FemModel< T > Class Template Referenceabstract

Detailed Description

template<typename T>
class drake::multibody::fem::FemModel< T >

FemModel calculates the components of the spatially discretized FEM equations for dynamic elasticity problems.

Typically, in dynamic elasticity problems, we are interested in the mapping that describes the motion of a material

ϕ(⋅,t) : Ω⁰ → Ωᵗ,

where Ω⁰ and Ωᵗ are subsets of R³, along with its first and second derivatives (velocity and acceleration respectively):

V(⋅,t) = ∂ϕ(⋅,t)/∂t,
A(⋅,t) = ∂²ϕ(⋅,t)/∂t².

We call Ω⁰ the reference domain and Ωᵗ the current domain. We use upper case letters to denote states (positions, velocities, and accelerations) in reference domain (X, V, A) and lower case letters to denote their current domain counterparts (x, v, a). In particular, x(X,t) = ϕ(X,t). The deformation gradient F(X,t) is given by ∂ϕ(X,t)/∂X.

The governing equations of interest are conservation of mass and conservation of momentum:

R(X,t)J(X,t) = R(X,0),
R(X,0)A(X,t) = fᵢₙₜ(X,t) + fₑₓₜ(X,t),

where R is mass density, fᵢₙₜ and fₑₓₜ are internal and external force densities respectively, and J is the determinant of the deformation gradient. Using finite element method to discretize in space, one gets

ϕ(X,t) = ∑ᵢ xᵢ(t)Nᵢ(X)
V(X,t) = ∑ᵢ vᵢ(t)Nᵢ(X)
A(X,t) = ∑ᵢ aᵢ(t)Nᵢ(X)

where xᵢ, vᵢ, aᵢ ∈ R³ are nodal values of the spatially discretized position, velocity and acceleration, and Nᵢ(X):Ω⁰ → R are the the basis functions. With this spatial discretization, the PDE is turned into an ODE of the form

G(x, v, a) = 0,            (1)

where x, v, a are the stacked xᵢ, vᵢ, aᵢ. FemModel provides methods to query various information about equation (1) and its derivatives given an FEM state (x, v, a).

We implement FemModel in FemModelImpl that templatizes on the type of FemElement. Many functionalities provided by FemModel (e.g. CalcTangentMatrix()) involve evaluating computationally intensive loops over FEM elements, and the overhead caused by virtual methods may be significant. We implement those functions in FemModelImpl templated on the FemElement to avoid the overhead of virtual methods. The type information at compile time also helps eliminate heap allocations.

Sifakis, Eftychios, and Jernej Barbič. "Finite element method simulation of 3d deformable solids." Synthesis Lectures on Visual Computing: Computer Graphics, Animation, Computational Photography, and Imaging 1.1 (2015): 1-69.

Template Parameters
TThe scalar type, which must be one of the default scalars.

#include <drake/multibody/fem/fem_model.h>

Classes

class  Builder
 Builder that builds the FemModel. More...
 

Public Member Functions

virtual ~FemModel ()
 
std::unique_ptr< FemModel< T > > Clone () const
 
int num_nodes () const
 The number of nodes that are associated with this model. More...
 
int num_dofs () const
 The number of degrees of freedom in this model. More...
 
virtual int num_elements () const =0
 The number of FEM elements in this model. More...
 
std::unique_ptr< FemState< T > > MakeFemState () const
 Creates a default FemState compatible with this model. More...
 
void CalcResidual (const FemState< T > &fem_state, const FemPlantData< T > &plant_data, EigenPtr< VectorX< T >> residual) const
 Calculates the residual G(x, v, a) (see class doc) evaluated at the given FEM state using the given plant_data. More...
 
void CalcTangentMatrix (const FemState< T > &fem_state, contact_solvers::internal::Block3x3SparseSymmetricMatrix *tangent_matrix) const
 Calculates an approximated tangent matrix evaluated at the given FEM state. More...
 
Vector3< T > CalcCenterOfMassPositionInWorld (const FemState< T > &fem_state) const
 Calculates the position vector from the world origin Wo to the center of mass of all bodies in this FemModel S, expressed in the world frame W. More...
 
Vector3< T > CalcCenterOfMassTranslationalVelocityInWorld (const FemState< T > &fem_state) const
 Calculates system center of mass translational velocity in world frame W. More...
 
Vector3< T > CalcEffectiveAngularVelocity (const FemState< T > &fem_state) const
 Using an angular momentum analogy, calculates an "effective" angular velocity for this FemModel S, measured and expressed in the world frame W. More...
 
std::unique_ptr< contact_solvers::internal::Block3x3SparseSymmetricMatrix > MakeTangentMatrix () const
 Creates a symmetric block sparse matrix that has the sparsity pattern of the tangent matrix of this FEM model. More...
 
void ApplyBoundaryCondition (FemState< T > *fem_state) const
 Applies boundary condition set for this FemModel to the input state. More...
 
void SetDirichletBoundaryCondition (const internal::DirichletBoundaryCondition< T > &dirichlet_bc)
 Sets the Dirichlet boundary condition that this model is subject to. More...
 
const internal::DirichletBoundaryCondition< T > & dirichlet_boundary_condition () const
 Returns the Dirichlet boundary condition that this model is subject to. More...
 
bool is_linear () const
 Returns true the equation G(x, v, a) = 0 (see class documentation) corresponding to this FemModel is linear. More...
 
bool is_compatible_with (const FemState< T > &state) const
 Returns true if the given FEM state is compatible with this FEM model. More...
 
const Vector3< T > & tangent_matrix_weights () const
 
void ThrowIfModelStateIncompatible (const char *func, const FemState< T > &fem_state) const
 (Internal use only) Throws std::exception to report a mismatch between the FEM model and state that were passed to API method func. More...
 
void set_parallelism (Parallelism parallelism)
 (Internal use only) Configures the parallelism that this FemModel uses when opportunities for parallel computation arises. More...
 
Parallelism parallelism () const
 (Internal use only) Returns the parallelism that this FemModel uses when opportunities for parallel computation arises. More...
 
get_total_mass () const
 Returns the total mass of the system. More...
 
Does not allow copy, move, or assignment
 FemModel (const FemModel &)=delete
 
FemModeloperator= (const FemModel &)=delete
 
 FemModel (FemModel &&)=delete
 
FemModeloperator= (FemModel &&)=delete
 

Protected Member Functions

 FemModel (const Vector3< T > &tangent_matrix_weights)
 Constructs an empty FEM model. More...
 
virtual std::unique_ptr< FemModel< T > > DoClone () const =0
 FemModelImpl must override this method to provide an implementation to make a deep copy of the concrete FemModel. More...
 
virtual VectorX< T > MakeReferencePositions () const =0
 Returns the reference positions of this model. More...
 
virtual void DoCalcResidual (const FemState< T > &fem_state, const FemPlantData< T > &plant_data, EigenPtr< VectorX< T >> residual) const =0
 FemModelImpl must override this method to provide an implementation for the NVI CalcResidual(). More...
 
virtual void DoCalcTangentMatrix (const FemState< T > &fem_state, contact_solvers::internal::Block3x3SparseSymmetricMatrix *tangent_matrix) const =0
 FemModelImpl must override this method to provide an implementation for the NVI CalcTangentMatrix(). More...
 
virtual Vector3< T > DoCalcCenterOfMassPositionInWorld (const FemState< T > &fem_state) const =0
 FemModelImpl must override this method to provide an implementation for the NVI CalcCenterOfMassPositionInWorld(). More...
 
virtual Vector3< T > DoCalcCenterOfMassTranslationalVelocityInWorld (const FemState< T > &fem_state) const =0
 FemModelImpl must override this method to provide an implementation for the NVI CalcCenterOfMassTranslationalVelocityInWorld(). More...
 
virtual Vector3< T > DoCalcEffectiveAngularVelocity (const FemState< T > &fem_state) const =0
 FemModelImpl must override this method to provide an implementation for the NVI CalcEffectiveAngularVelocity(). More...
 
virtual std::unique_ptr< contact_solvers::internal::Block3x3SparseSymmetricMatrix > DoMakeTangentMatrix () const =0
 FemModelImpl must override this method to provide an implementation for the NVI MakeTangentMatrix(). More...
 
void UpdateFemStateSystem ()
 Updates the system that manages the states and the cache entries of this FEM model. More...
 
virtual void DeclareCacheEntries (internal::FemStateSystem< T > *fem_state_system)=0
 Derived classes should override this method to declare cache entries in the given fem_state_system. More...
 
virtual bool do_is_linear () const =0
 Derived classes should override this method to indicate if the model is linear. More...
 
const internal::FemStateSystem< T > & fem_state_system () const
 Returns the FemStateSystem that manages the states and cache entries in this FemModel. More...
 

Constructor & Destructor Documentation

◆ FemModel() [1/3]

FemModel ( const FemModel< T > &  )
delete

◆ FemModel() [2/3]

FemModel ( FemModel< T > &&  )
delete

◆ ~FemModel()

virtual ~FemModel ( )
virtual

◆ FemModel() [3/3]

FemModel ( const Vector3< T > &  tangent_matrix_weights)
explicitprotected

Constructs an empty FEM model.

Precondition
tangent_matrix_weights.minCoeff() >= 0.0.

Member Function Documentation

◆ ApplyBoundaryCondition()

void ApplyBoundaryCondition ( FemState< T > *  fem_state) const

Applies boundary condition set for this FemModel to the input state.

No-op if no boundary condition is set.

Precondition
fem_state != nullptr.
Exceptions
std::exceptionif the FEM state is incompatible with this model.

◆ CalcCenterOfMassPositionInWorld()

Vector3<T> CalcCenterOfMassPositionInWorld ( const FemState< T > &  fem_state) const

Calculates the position vector from the world origin Wo to the center of mass of all bodies in this FemModel S, expressed in the world frame W.

Parameters
[in]fem_stateThe FemState used to evaluate the center of mass.
Return values
p_WoScm_Wposition vector from Wo to Scm expressed in world frame W, where Scm is the center of mass of the system S stored by this FemModel.
Exceptions
std::exceptionif the FEM state is incompatible with this model.

◆ CalcCenterOfMassTranslationalVelocityInWorld()

Vector3<T> CalcCenterOfMassTranslationalVelocityInWorld ( const FemState< T > &  fem_state) const

Calculates system center of mass translational velocity in world frame W.

Parameters
[in]fem_stateThe FemState used for this calculation.
Return values
v_WScm_WScm's translational velocity in frame W, expressed in W, where Scm is the center of mass of the system S stored by this FemModel.
Exceptions
std::exceptionif the FEM state is incompatible with this model.

◆ CalcEffectiveAngularVelocity()

Vector3<T> CalcEffectiveAngularVelocity ( const FemState< T > &  fem_state) const

Using an angular momentum analogy, calculates an "effective" angular velocity for this FemModel S, measured and expressed in the world frame W.

The effective angular velocity is computed using an angular momentum equation that assumes S is a rigid body (albeit we know S is deformable).

 H_WSSm_W = I_SScm_W * w_WScm_W

for which when solved for w_WScm_W gives

 w_WScm_W = inverse(I_SScm_W) * H_WSSm_W

where H_WSSm_W is the FemModel S's angular momentum about its center of mass Scm measured and expressed in the world frame W.

Parameters
[in]fem_stateThe FemState used for this calculation.
Return values
w_WScm_Wthe FemModel S's effective angular velocity for Scm, measured and expressed in the world frame W.
Exceptions
std::exceptionif the FEM state is incompatible with this model.

◆ CalcResidual()

void CalcResidual ( const FemState< T > &  fem_state,
const FemPlantData< T > &  plant_data,
EigenPtr< VectorX< T >>  residual 
) const

Calculates the residual G(x, v, a) (see class doc) evaluated at the given FEM state using the given plant_data.

The residual for degrees of freedom with Dirichlet boundary conditions is set to zero. Therefore their residual should not be used as a metric for the error on the boundary condition.

Precondition
residual != nullptr.
Exceptions
std::exceptionif the FEM state is incompatible with this model.

◆ CalcTangentMatrix()

void CalcTangentMatrix ( const FemState< T > &  fem_state,
contact_solvers::internal::Block3x3SparseSymmetricMatrix *  tangent_matrix 
) const

Calculates an approximated tangent matrix evaluated at the given FEM state.

The tangent matrix is given by a weighted sum of stiffness matrix (∂G/∂x), damping matrix (∂G/∂v), and mass matrix (∂G/∂a). The corresponding row and column for a degree of freedom with Dirichlet boundary condition in the tangent matrix is set to zero with the exception of the diagonal entries which is set to a scalar multiple of identity.

Parameters
[in]fem_stateThe FemState used to evaluate the tangent matrix.
[out]tangent_matrixThe output tangent_matrix.
Precondition
tangent_matrix != nullptr.
The size of tangent_matrix is num_dofs() * num_dofs().
All nonzero entries in the resulting tangent matrix have been allocated. See MakeTangentMatrix().
Warning
This function sometimes makes simplifying approximations to avoid taking overly complicated derivatives. As such, the resulting tangent matrix may be an approximation of the actual value depending on the constitutive model used.
Exceptions
std::exceptionif the FEM state is incompatible with this model.
std::exceptionif T is not double.

◆ Clone()

std::unique_ptr<FemModel<T> > Clone ( ) const

◆ DeclareCacheEntries()

virtual void DeclareCacheEntries ( internal::FemStateSystem< T > *  fem_state_system)
protectedpure virtual

Derived classes should override this method to declare cache entries in the given fem_state_system.

◆ dirichlet_boundary_condition()

const internal::DirichletBoundaryCondition<T>& dirichlet_boundary_condition ( ) const

Returns the Dirichlet boundary condition that this model is subject to.

◆ do_is_linear()

virtual bool do_is_linear ( ) const
protectedpure virtual

Derived classes should override this method to indicate if the model is linear.

◆ DoCalcCenterOfMassPositionInWorld()

virtual Vector3<T> DoCalcCenterOfMassPositionInWorld ( const FemState< T > &  fem_state) const
protectedpure virtual

FemModelImpl must override this method to provide an implementation for the NVI CalcCenterOfMassPositionInWorld().

The input fem_state is guaranteed to be compatible with this FEM model.

◆ DoCalcCenterOfMassTranslationalVelocityInWorld()

virtual Vector3<T> DoCalcCenterOfMassTranslationalVelocityInWorld ( const FemState< T > &  fem_state) const
protectedpure virtual

FemModelImpl must override this method to provide an implementation for the NVI CalcCenterOfMassTranslationalVelocityInWorld().

The input fem_state is guaranteed to be compatible with this FEM model.

◆ DoCalcEffectiveAngularVelocity()

virtual Vector3<T> DoCalcEffectiveAngularVelocity ( const FemState< T > &  fem_state) const
protectedpure virtual

FemModelImpl must override this method to provide an implementation for the NVI CalcEffectiveAngularVelocity().

The input fem_state is guaranteed to be compatible with this FEM model.

◆ DoCalcResidual()

virtual void DoCalcResidual ( const FemState< T > &  fem_state,
const FemPlantData< T > &  plant_data,
EigenPtr< VectorX< T >>  residual 
) const
protectedpure virtual

FemModelImpl must override this method to provide an implementation for the NVI CalcResidual().

The input fem_state is guaranteed to be compatible with this FEM model, and the input residual is guaranteed to be non-null and properly sized.

◆ DoCalcTangentMatrix()

virtual void DoCalcTangentMatrix ( const FemState< T > &  fem_state,
contact_solvers::internal::Block3x3SparseSymmetricMatrix *  tangent_matrix 
) const
protectedpure virtual

FemModelImpl must override this method to provide an implementation for the NVI CalcTangentMatrix().

The input fem_state is guaranteed to be compatible with this FEM model, and the input tangent_matrix is guaranteed to be non-null and properly sized.

◆ DoClone()

virtual std::unique_ptr<FemModel<T> > DoClone ( ) const
protectedpure virtual

FemModelImpl must override this method to provide an implementation to make a deep copy of the concrete FemModel.

◆ DoMakeTangentMatrix()

virtual std::unique_ptr< contact_solvers::internal::Block3x3SparseSymmetricMatrix> DoMakeTangentMatrix ( ) const
protectedpure virtual

FemModelImpl must override this method to provide an implementation for the NVI MakeTangentMatrix().

◆ fem_state_system()

const internal::FemStateSystem<T>& fem_state_system ( ) const
protected

Returns the FemStateSystem that manages the states and cache entries in this FemModel.

◆ get_total_mass()

T get_total_mass ( ) const

Returns the total mass of the system.

◆ is_compatible_with()

bool is_compatible_with ( const FemState< T > &  state) const

Returns true if the given FEM state is compatible with this FEM model.

◆ is_linear()

bool is_linear ( ) const

Returns true the equation G(x, v, a) = 0 (see class documentation) corresponding to this FemModel is linear.

◆ MakeFemState()

std::unique_ptr<FemState<T> > MakeFemState ( ) const

Creates a default FemState compatible with this model.

◆ MakeReferencePositions()

virtual VectorX<T> MakeReferencePositions ( ) const
protectedpure virtual

Returns the reference positions of this model.

◆ MakeTangentMatrix()

std::unique_ptr<contact_solvers::internal::Block3x3SparseSymmetricMatrix> MakeTangentMatrix ( ) const

Creates a symmetric block sparse matrix that has the sparsity pattern of the tangent matrix of this FEM model.

In particular, the size of the tangent matrix is num_dofs() by num_dofs(). All entries are initialized to zero.

Exceptions
std::exceptionif T is not double.

◆ num_dofs()

int num_dofs ( ) const

The number of degrees of freedom in this model.

◆ num_elements()

virtual int num_elements ( ) const
pure virtual

The number of FEM elements in this model.

◆ num_nodes()

int num_nodes ( ) const

The number of nodes that are associated with this model.

◆ operator=() [1/2]

FemModel& operator= ( FemModel< T > &&  )
delete

◆ operator=() [2/2]

FemModel& operator= ( const FemModel< T > &  )
delete

◆ parallelism()

Parallelism parallelism ( ) const

(Internal use only) Returns the parallelism that this FemModel uses when opportunities for parallel computation arises.

◆ set_parallelism()

void set_parallelism ( Parallelism  parallelism)

(Internal use only) Configures the parallelism that this FemModel uses when opportunities for parallel computation arises.

◆ SetDirichletBoundaryCondition()

void SetDirichletBoundaryCondition ( const internal::DirichletBoundaryCondition< T > &  dirichlet_bc)

Sets the Dirichlet boundary condition that this model is subject to.

If dirichlet_bc specifies the boundary condition for a node for which a boundary condition has already been specified, the lastest one will be used.

◆ tangent_matrix_weights()

const Vector3<T>& tangent_matrix_weights ( ) const

◆ ThrowIfModelStateIncompatible()

void ThrowIfModelStateIncompatible ( const char *  func,
const FemState< T > &  fem_state 
) const

(Internal use only) Throws std::exception to report a mismatch between the FEM model and state that were passed to API method func.

◆ UpdateFemStateSystem()

void UpdateFemStateSystem ( )
protected

Updates the system that manages the states and the cache entries of this FEM model.

Must be called before calling MakeFemState() after the FEM model changes (e.g. adding new elements).


The documentation for this class was generated from the following file: