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.
| T | The 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. | |
| std::unique_ptr< ForceDensityFieldBase< T > > | Clone () const |
| Returns an identical copy of this ForceDensityFieldBase. | |
| 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(). | |
| virtual std::unique_ptr< ForceDensityFieldBase< T > > | DoClone () const =0 |
| Derived classes must override this function to implement the NVI Clone(). | |
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable | |
| ForceDensityFieldBase (const ForceDensityFieldBase &)=default | |
| ForceDensityFieldBase & | operator= (const ForceDensityFieldBase &)=default |
| ForceDensityFieldBase (ForceDensityFieldBase &&)=default | |
| ForceDensityFieldBase & | operator= (ForceDensityFieldBase &&)=default |
Friends | |
| class | ForceDensityField< T > |
|
pure virtual |
|
protecteddefault |
|
protecteddefault |
| std::unique_ptr< ForceDensityFieldBase< T > > Clone | ( | ) | const |
Returns an identical copy of this ForceDensityFieldBase.
| ForceDensityType density_type | ( | ) | const |
|
protectedpure virtual |
Derived classes must override this function to implement the NVI Clone().
|
protectedpure virtual |
Derived classes must override this function to provide a threadsafe implemention to the NVI 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.
|
protecteddefault |
|
protecteddefault |
|
friend |