The ForceDensityField 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³]. The force density function can depend on other Context-dependent parameters.
T | The scalar type, which must be one of the default scalars. |
#include <drake/multibody/tree/multibody_tree_system.h>
Public Member Functions | |
virtual | ~ForceDensityField () |
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< ForceDensityField< T > > | Clone () const |
Returns an identical copy of this ForceDensityField. More... | |
bool | has_parent_system () const |
Returns true iff this external force is owned by a MultibodyPlant. More... | |
const systems::LeafSystem< T > & | parent_system_or_throw () const |
Returns the owning MultibodyPlant LeafSystem. More... | |
ForceDensityType | density_type () const |
Protected Member Functions | |
ForceDensityField (ForceDensityType density_type=ForceDensityType::kPerCurrentVolume) | |
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< ForceDensityField< T > > | DoClone () const =0 |
Derived classes must override this function to implement the NVI Clone(). More... | |
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable | |
ForceDensityField (const ForceDensityField &)=default | |
ForceDensityField & | operator= (const ForceDensityField &)=default |
ForceDensityField (ForceDensityField &&)=default | |
ForceDensityField & | operator= (ForceDensityField &&)=default |
virtual void | DoDeclareCacheEntries (MultibodyPlant< T > *) |
NVI implementations for declaring system resources. More... | |
virtual void | DoDeclareInputPorts (MultibodyPlant< T > *) |
static systems::CacheEntry & | DeclareCacheEntry (internal::MultibodyTreeSystem< T > *plant, std::string description, systems::ValueProducer value_producer, std::set< systems::DependencyTicket > prerequisites_of_calc) |
}@ More... | |
static systems::InputPort< T > & | DeclareAbstractInputPort (internal::MultibodyTreeSystem< T > *plant, std::string name, const AbstractValue &model_value) |
static systems::InputPort< T > & | DeclareVectorInputPort (internal::MultibodyTreeSystem< T > *plant, std::string name, const systems::BasicVector< T > &model_vector) |
|
virtual |
|
protecteddefault |
|
protecteddefault |
|
explicitprotected |
std::unique_ptr<ForceDensityField<T> > Clone | ( | ) | const |
Returns an identical copy of this
ForceDensityField.
|
staticprotected |
|
staticprotected |
}@
Protected LeafSystem methods exposed to declare system resources in a MultibodyPlant. DoDeclareCacheEntries() and DoDeclareInputPorts() can use these to declare cache entries and input ports.
|
staticprotected |
ForceDensityType density_type | ( | ) | const |
|
protectedpure virtual |
Derived classes must override this function to implement the NVI Clone().
|
protectedvirtual |
NVI implementations for declaring system resources.
Defaults to no-op. Derived classes should override the default implementation if the external force field is Context-dependent.
|
protectedvirtual |
|
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
.
bool has_parent_system | ( | ) | const |
Returns true iff this
external force is owned by a MultibodyPlant.
|
protecteddefault |
|
protecteddefault |
const systems::LeafSystem<T>& parent_system_or_throw | ( | ) | const |
Returns the owning MultibodyPlant LeafSystem.
std::exception | if this force density field is not owned by any system. |