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

Detailed Description

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

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.

Template Parameters
TThe 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
 
ForceDensityFieldoperator= (const ForceDensityField &)=default
 
 ForceDensityField (ForceDensityField &&)=default
 
ForceDensityFieldoperator= (ForceDensityField &&)=default
 
virtual void DoDeclareCacheEntries (MultibodyPlant< T > *)
 NVI implementations for declaring system resources. More...
 
virtual void DoDeclareInputPorts (MultibodyPlant< T > *)
 
static systems::CacheEntryDeclareCacheEntry (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)
 

Constructor & Destructor Documentation

◆ ~ForceDensityField()

virtual ~ForceDensityField ( )
virtual

◆ ForceDensityField() [1/3]

ForceDensityField ( const ForceDensityField< T > &  )
protecteddefault

◆ ForceDensityField() [2/3]

ForceDensityField ( ForceDensityField< T > &&  )
protecteddefault

◆ ForceDensityField() [3/3]

Member Function Documentation

◆ Clone()

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

Returns an identical copy of this ForceDensityField.

◆ DeclareAbstractInputPort()

static systems::InputPort<T>& DeclareAbstractInputPort ( internal::MultibodyTreeSystem< T > *  plant,
std::string  name,
const AbstractValue model_value 
)
staticprotected

◆ DeclareCacheEntry()

static systems::CacheEntry& DeclareCacheEntry ( internal::MultibodyTreeSystem< T > *  plant,
std::string  description,
systems::ValueProducer  value_producer,
std::set< systems::DependencyTicket prerequisites_of_calc 
)
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.

◆ DeclareVectorInputPort()

static systems::InputPort<T>& DeclareVectorInputPort ( internal::MultibodyTreeSystem< T > *  plant,
std::string  name,
const systems::BasicVector< T > &  model_vector 
)
staticprotected

◆ density_type()

ForceDensityType density_type ( ) const

◆ DoClone()

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

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

◆ DoDeclareCacheEntries()

virtual void DoDeclareCacheEntries ( MultibodyPlant< T > *  )
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.

◆ DoDeclareInputPorts()

virtual void DoDeclareInputPorts ( MultibodyPlant< T > *  )
protectedvirtual

◆ 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.

◆ has_parent_system()

bool has_parent_system ( ) const

Returns true iff this external force is owned by a MultibodyPlant.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ parent_system_or_throw()

const systems::LeafSystem<T>& parent_system_or_throw ( ) const

Returns the owning MultibodyPlant LeafSystem.

Exceptions
std::exceptionif this force density field is not owned by any system.

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