Drake
Drake C++ Documentation
PointSourceForceField Class Referencefinal

#include <drake/examples/multibody/deformable/point_source_force_field.h>

Public Member Functions

 PointSourceForceField (const multibody::MultibodyPlant< double > &plant, const multibody::RigidBody< double > &body, const Vector3< double > &p_BC, double falloff_distance)
 
const systems::InputPort< double > & maximum_force_density_input_port () const
 
Does not allow copy, move, or assignment
 PointSourceForceField (const PointSourceForceField &)=delete
 
PointSourceForceFieldoperator= (const PointSourceForceField &)=delete
 
 PointSourceForceField (PointSourceForceField &&)=delete
 
PointSourceForceFieldoperator= (PointSourceForceField &&)=delete
 
- Public Member Functions inherited from ForceDensityField< double >
virtual ~ForceDensityField ()=default
 
Vector3< doubleEvaluateAt (const systems::Context< double > &context, const Vector3< double > &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< double > > 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< double > & parent_system_or_throw () const
 Returns the owning MultibodyPlant LeafSystem. More...
 
ForceDensityType density_type () const
 

Additional Inherited Members

- Protected Member Functions inherited from ForceDensityField< double >
 ForceDensityField (ForceDensityType density_type=ForceDensityType::kPerCurrentVolume)
 
 ForceDensityField (const ForceDensityField &)=default
 
 ForceDensityField (ForceDensityField &&)=default
 
ForceDensityFieldoperator= (const ForceDensityField &)=default
 
ForceDensityFieldoperator= (ForceDensityField &&)=default
 
- Static Protected Member Functions inherited from ForceDensityField< double >
static systems::CacheEntryDeclareCacheEntry (internal::MultibodyTreeSystem< double > *plant, std::string description, systems::ValueProducer value_producer, std::set< systems::DependencyTicket > prerequisites_of_calc)
 }@ More...
 
static systems::InputPort< double > & DeclareAbstractInputPort (internal::MultibodyTreeSystem< double > *plant, std::string name, const AbstractValue &model_value)
 
static systems::InputPort< double > & DeclareVectorInputPort (internal::MultibodyTreeSystem< double > *plant, std::string name, const systems::BasicVector< double > &model_vector)
 

Constructor & Destructor Documentation

◆ PointSourceForceField() [1/3]

◆ PointSourceForceField() [2/3]

◆ PointSourceForceField() [3/3]

PointSourceForceField ( const multibody::MultibodyPlant< double > &  plant,
const multibody::RigidBody< double > &  body,
const Vector3< double > &  p_BC,
double  falloff_distance 
)

Member Function Documentation

◆ maximum_force_density_input_port()

const systems::InputPort<double>& maximum_force_density_input_port ( ) const

◆ operator=() [1/2]

PointSourceForceField& operator= ( const PointSourceForceField )
delete

◆ operator=() [2/2]

PointSourceForceField& operator= ( PointSourceForceField &&  )
delete

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