A uniform gravitational force density field for a uniform density object.
The force density f [N/m³] is given by the product of mass density ρ [kg/m³] and gravity vector g [m/s²].
T | The scalar type, which must be one of the default scalars. |
#include <drake/multibody/plant/force_density_field.h>
Public Member Functions | |
GravityForceField (const Vector3< T > &gravity_vector, const T &mass_density) | |
Constructs a uniform gravitational force density field for a uniform density object with the given gravity_vector [m/s²] and mass_density [kg/m³] in the reference (undeformed) configuration where the reference (undeformed) configuration is defined by the input mesh provided by the user. More... | |
~GravityForceField () override | |
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable | |
GravityForceField (const GravityForceField &)=default | |
GravityForceField & | operator= (const GravityForceField &)=default |
GravityForceField (GravityForceField &&)=default | |
GravityForceField & | operator= (GravityForceField &&)=default |
Public Member Functions inherited from ForceDensityField< T > | |
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 |
Additional Inherited Members | |
Protected Member Functions inherited from ForceDensityField< T > | |
ForceDensityField (ForceDensityType density_type=ForceDensityType::kPerCurrentVolume) | |
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 Protected Member Functions inherited from ForceDensityField< 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) |
|
default |
|
default |
GravityForceField | ( | const Vector3< T > & | gravity_vector, |
const T & | mass_density | ||
) |
Constructs a uniform gravitational force density field for a uniform density object with the given gravity_vector
[m/s²] and mass_density
[kg/m³] in the reference (undeformed) configuration where the reference (undeformed) configuration is defined by the input mesh provided by the user.
|
override |
|
default |
|
default |