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

Detailed Description

template<typename T>
class drake::multibody::ForceDensityFieldBase< T >

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.

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

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

Public Member Functions

virtual ~ForceDensityFieldBase ()=0
 
Vector3< T > EvaluateAt (const systems::Context< T > &context, const Vector3< T > &p_WQ) const
 Evaluates the force density [N/m³] with the given context of the owning MultibodyPlant and a position in world, p_WQ. More...
 
std::unique_ptr< ForceDensityFieldBase< T > > Clone () const
 Returns an identical copy of this ForceDensityFieldBase. More...
 
ForceDensityType density_type () const
 

Protected Member Functions

virtual Vector3< T > DoEvaluateAt (const systems::Context< T > &context, const Vector3< T > &p_WQ) const =0
 Derived classes must override this function to provide a threadsafe implemention to the NVI EvaluateAt(). More...
 
virtual std::unique_ptr< ForceDensityFieldBase< T > > DoClone () const =0
 Derived classes must override this function to implement the NVI Clone(). More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 ForceDensityFieldBase (const ForceDensityFieldBase &)=default
 
ForceDensityFieldBaseoperator= (const ForceDensityFieldBase &)=default
 
 ForceDensityFieldBase (ForceDensityFieldBase &&)=default
 
ForceDensityFieldBaseoperator= (ForceDensityFieldBase &&)=default
 

Friends

class ForceDensityField< T >
 

Constructor & Destructor Documentation

◆ ~ForceDensityFieldBase()

virtual ~ForceDensityFieldBase ( )
pure virtual

◆ ForceDensityFieldBase() [1/2]

ForceDensityFieldBase ( const ForceDensityFieldBase< T > &  )
protecteddefault

◆ ForceDensityFieldBase() [2/2]

ForceDensityFieldBase ( ForceDensityFieldBase< T > &&  )
protecteddefault

Member Function Documentation

◆ Clone()

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

Returns an identical copy of this ForceDensityFieldBase.

◆ density_type()

ForceDensityType density_type ( ) const

◆ DoClone()

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

Derived classes must override this function to implement the NVI Clone().

◆ DoEvaluateAt()

virtual Vector3<T> DoEvaluateAt ( const systems::Context< T > &  context,
const Vector3< T > &  p_WQ 
) const
protectedpure virtual

Derived classes must override this function to provide a threadsafe implemention to the NVI EvaluateAt().

◆ EvaluateAt()

Vector3<T> EvaluateAt ( const systems::Context< T > &  context,
const Vector3< T > &  p_WQ 
) const

Evaluates the force density [N/m³] with the given context of the owning MultibodyPlant and a position in world, p_WQ.

◆ operator=() [1/2]

ForceDensityFieldBase& operator= ( ForceDensityFieldBase< T > &&  )
protecteddefault

◆ operator=() [2/2]

ForceDensityFieldBase& operator= ( const ForceDensityFieldBase< T > &  )
protecteddefault

Friends And Related Function Documentation

◆ ForceDensityField< T >

friend class ForceDensityField< T >
friend

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