Drake
Drake C++ Documentation
UniformGravityFieldElement< T > Class Template Reference

Detailed Description

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

This ForceElement allows modeling the effect of a uniform gravity field as felt by bodies on the surface of the Earth.

This gravity field acts on all bodies in the MultibodyTree model.

Template Parameters
TThe scalar type, which must be one of the default scalars.

#include <drake/multibody/tree/uniform_gravity_field_element.h>

Public Member Functions

 UniformGravityFieldElement ()
 Constructs a uniform gravity field element with a default strength (on the earth's surface) and direction (-z). More...
 
 UniformGravityFieldElement (Vector3< double > g_W)
 Constructs a uniform gravity field element with a strength given by the acceleration of gravity vector g_W, expressed in the world frame W. More...
 
 UniformGravityFieldElement (Vector3< double > g_W, std::set< ModelInstanceIndex > disabled_model_instances)
 Constructs a uniform gravity field element with a strength given by the acceleration of gravity vector g_W, expressed in the world frame W. More...
 
const Vector3< double > & gravity_vector () const
 Returns the acceleration of the gravity vector in m/s², expressed in the world frame W. More...
 
void set_gravity_vector (const Vector3< double > &g_W)
 Sets the acceleration of gravity vector, expressed in the world frame W in m/s². More...
 
bool is_enabled (ModelInstanceIndex model_instance) const
 
void set_enabled (ModelInstanceIndex model_instance, bool is_enabled)
 Sets is_enabled() for model_instance to is_enabled. More...
 
VectorX< T > CalcGravityGeneralizedForces (const systems::Context< T > &context) const
 Computes the generalized forces tau_g(q) due to this gravity field element as a function of the generalized positions q stored in the input context, for the multibody model to which this element belongs. More...
 
CalcPotentialEnergy (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc) const final
 Computes the total potential energy of all bodies in the model in this uniform gravity field. More...
 
CalcConservativePower (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc, const internal::VelocityKinematicsCache< T > &vc) const final
 (Advanced) Calculates and returns the power generated by conservative force elements or zero if this force element is non-conservative. More...
 
CalcNonConservativePower (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc, const internal::VelocityKinematicsCache< T > &vc) const final
 (Advanced) Calculates the rate at which mechanical energy is being generated (positive) or dissipated (negative) other than by conversion between potential and kinetic energy. More...
 
Does not allow copy, move, or assignment
 UniformGravityFieldElement (const UniformGravityFieldElement &)=delete
 
UniformGravityFieldElementoperator= (const UniformGravityFieldElement &)=delete
 
 UniformGravityFieldElement (UniformGravityFieldElement &&)=delete
 
UniformGravityFieldElementoperator= (UniformGravityFieldElement &&)=delete
 
- Public Member Functions inherited from ForceElement< T >
 ForceElement (ModelInstanceIndex model_instance)
 Default constructor for a generic force element. More...
 
ForceElementIndex index () const
 Returns this element's unique index. More...
 
void CalcAndAddForceContribution (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc, const internal::VelocityKinematicsCache< T > &vc, MultibodyForces< T > *forces) const
 (Advanced) Computes the force contribution for this force element and adds it to the output arrays of forces. More...
 
 ForceElement (const ForceElement &)=delete
 
ForceElementoperator= (const ForceElement &)=delete
 
 ForceElement (ForceElement &&)=delete
 
ForceElementoperator= (ForceElement &&)=delete
 
- Public Member Functions inherited from MultibodyElement< T >
virtual ~MultibodyElement ()
 
ModelInstanceIndex model_instance () const
 Returns the ModelInstanceIndex of the model instance to which this element belongs. More...
 
template<typename MultibodyPlantDeferred = MultibodyPlant<T>>
const MultibodyPlantDeferred & GetParentPlant () const
 Returns the MultibodyPlant that owns this MultibodyElement. More...
 
void DeclareParameters (internal::MultibodyTreeSystem< T > *tree_system)
 Declares MultibodyTreeSystem Parameters at MultibodyTreeSystem::Finalize() time. More...
 
void SetDefaultParameters (systems::Parameters< T > *parameters) const
 Sets default values of parameters belonging to each MultibodyElement in parameters at a call to MultibodyTreeSystem::SetDefaultParameters(). More...
 
 MultibodyElement (const MultibodyElement &)=delete
 
MultibodyElementoperator= (const MultibodyElement &)=delete
 
 MultibodyElement (MultibodyElement &&)=delete
 
MultibodyElementoperator= (MultibodyElement &&)=delete
 

Static Public Attributes

static constexpr double kDefaultStrength = 9.81
 The strength used by our class's default constructor (i.e., on the earth's surface). More...
 

Protected Member Functions

void DoCalcAndAddForceContribution (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc, const internal::VelocityKinematicsCache< T > &vc, MultibodyForces< T > *forces) const final
 This method is called only from the public non-virtual CalcAndAddForceContributions() which will already have error-checked the parameters so you don't have to. More...
 
std::unique_ptr< ForceElement< double > > DoCloneToScalar (const internal::MultibodyTree< double > &tree_clone) const override
 Clones this ForceElement (templated on T) to a mobilizer templated on double. More...
 
std::unique_ptr< ForceElement< AutoDiffXd > > DoCloneToScalar (const internal::MultibodyTree< AutoDiffXd > &tree_clone) const override
 Clones this ForceElement (templated on T) to a mobilizer templated on AutoDiffXd. More...
 
std::unique_ptr< ForceElement< symbolic::Expression > > DoCloneToScalar (const internal::MultibodyTree< symbolic::Expression > &) const override
 
- Protected Member Functions inherited from ForceElement< T >
virtual void DoDeclareForceElementParameters (internal::MultibodyTreeSystem< T > *)
 Called by DoDeclareParameters(). More...
 
virtual void DoSetDefaultForceElementParameters (systems::Parameters< T > *) const
 Called by DoSetDefaultParameters(). More...
 
- Protected Member Functions inherited from MultibodyElement< T >
 MultibodyElement ()
 Default constructor made protected so that sub-classes can still declare their default constructors if they need to. More...
 
 MultibodyElement (ModelInstanceIndex model_instance)
 Constructor which allows specifying a model instance. More...
 
 MultibodyElement (ModelInstanceIndex model_instance, int64_t index)
 Both the model instance and element index are specified. More...
 
template<typename ElementIndexType >
ElementIndexType index_impl () const
 Returns this element's unique index. More...
 
const internal::MultibodyTree< T > & get_parent_tree () const
 Returns a constant reference to the parent MultibodyTree that owns this element. More...
 
const internal::MultibodyTreeSystem< T > & GetParentTreeSystem () const
 Returns a constant reference to the parent MultibodyTreeSystem that owns the parent MultibodyTree that owns this element. More...
 
void SetTopology (const internal::MultibodyTreeTopology &tree)
 Gives MultibodyElement-derived objects the opportunity to retrieve their topology after MultibodyTree::Finalize() is invoked. More...
 
systems::NumericParameterIndex DeclareNumericParameter (internal::MultibodyTreeSystem< T > *tree_system, const systems::BasicVector< T > &model_vector)
 To be used by MultibodyElement-derived objects when declaring parameters in their implementation of DoDeclareParameters(). More...
 
systems::AbstractParameterIndex DeclareAbstractParameter (internal::MultibodyTreeSystem< T > *tree_system, const AbstractValue &model_value)
 To be used by MultibodyElement-derived objects when declaring parameters in their implementation of DoDeclareParameters(). More...
 

Constructor & Destructor Documentation

◆ UniformGravityFieldElement() [1/5]

◆ UniformGravityFieldElement() [2/5]

◆ UniformGravityFieldElement() [3/5]

Constructs a uniform gravity field element with a default strength (on the earth's surface) and direction (-z).

◆ UniformGravityFieldElement() [4/5]

Constructs a uniform gravity field element with a strength given by the acceleration of gravity vector g_W, expressed in the world frame W.

◆ UniformGravityFieldElement() [5/5]

UniformGravityFieldElement ( Vector3< double g_W,
std::set< ModelInstanceIndex disabled_model_instances 
)

Constructs a uniform gravity field element with a strength given by the acceleration of gravity vector g_W, expressed in the world frame W.

Gravity is disabled for the set of model instances disabled_model_instances.

Member Function Documentation

◆ CalcConservativePower()

T CalcConservativePower ( const systems::Context< T > &  context,
const internal::PositionKinematicsCache< T > &  pc,
const internal::VelocityKinematicsCache< T > &  vc 
) const
finalvirtual

(Advanced) Calculates and returns the power generated by conservative force elements or zero if this force element is non-conservative.

This quantity is defined to be positive when the potential energy is decreasing. In other words, if PE is the potential energy as defined by CalcPotentialEnergy(), then the conservative power, Pc, is Pc = -d(PE)/dt.

See also
CalcPotentialEnergy(), CalcNonConservativePower()

Implements ForceElement< T >.

◆ CalcGravityGeneralizedForces()

VectorX<T> CalcGravityGeneralizedForces ( const systems::Context< T > &  context) const

Computes the generalized forces tau_g(q) due to this gravity field element as a function of the generalized positions q stored in the input context, for the multibody model to which this element belongs.

tau_g(q) is defined such that it appears on the right hand side of the equations of motion together with any other generalized forces, like so:

  Mv̇ + C(q, v)v = tau_g(q) + tau_app

where tau_app includes any other generalized forces applied on the system.

Parameters
[in]contextThe context storing the state of the multibody model to which this element belongs.
Returns
tau_g A vector containing the generalized forces due to this gravity field force element. The generalized forces are consistent with the vector of generalized velocities v for the parent MultibodyTree model so that the inner product v⋅tau_g corresponds to the power applied by the gravity forces on the mechanical system. That is, v⋅tau_g > 0 corresponds to potential energy going into the system, as either mechanical kinetic energy, some other potential energy, or heat, and therefore to a decrease of potential energy.

◆ CalcNonConservativePower()

T CalcNonConservativePower ( const systems::Context< T > &  context,
const internal::PositionKinematicsCache< T > &  pc,
const internal::VelocityKinematicsCache< T > &  vc 
) const
finalvirtual

(Advanced) Calculates the rate at which mechanical energy is being generated (positive) or dissipated (negative) other than by conversion between potential and kinetic energy.

Integrating this quantity yields work W, and the total energy E = PE + KE - W should be conserved by any physically-correct model, to within integration accuracy of W.

See also
CalcConservativePower()

Implements ForceElement< T >.

◆ CalcPotentialEnergy()

T CalcPotentialEnergy ( const systems::Context< T > &  context,
const internal::PositionKinematicsCache< T > &  pc 
) const
finalvirtual

Computes the total potential energy of all bodies in the model in this uniform gravity field.

The definition of potential energy allows to arbitrarily choose the zero energy height. This element takes the zero energy height to be the same as the world's height. That is, a body will have zero potential energy when its the height of its center of mass is at the world's origin.

Implements ForceElement< T >.

◆ DoCalcAndAddForceContribution()

void DoCalcAndAddForceContribution ( const systems::Context< T > &  context,
const internal::PositionKinematicsCache< T > &  pc,
const internal::VelocityKinematicsCache< T > &  vc,
MultibodyForces< T > *  forces 
) const
finalprotectedvirtual

This method is called only from the public non-virtual CalcAndAddForceContributions() which will already have error-checked the parameters so you don't have to.

Refer to the documentation for CalcAndAddForceContribution() for details describing the purpose and parameters of this method. It assumes forces to be a valid pointer to a MultibodyForces object compatible with the MultibodyTree model owning this force element.

Precondition
The position kinematics pc must have been previously updated with a call to CalcPositionKinematicsCache().
The velocity kinematics vc must have been previously updated with a call to CalcVelocityKinematicsCache().

Implements ForceElement< T >.

◆ DoCloneToScalar() [1/3]

std::unique_ptr<ForceElement<double> > DoCloneToScalar ( const internal::MultibodyTree< double > &  tree_clone) const
overrideprotectedvirtual

Clones this ForceElement (templated on T) to a mobilizer templated on double.

Implements ForceElement< T >.

◆ DoCloneToScalar() [2/3]

std::unique_ptr<ForceElement<AutoDiffXd> > DoCloneToScalar ( const internal::MultibodyTree< AutoDiffXd > &  tree_clone) const
overrideprotectedvirtual

Clones this ForceElement (templated on T) to a mobilizer templated on AutoDiffXd.

Implements ForceElement< T >.

◆ DoCloneToScalar() [3/3]

std::unique_ptr<ForceElement<symbolic::Expression> > DoCloneToScalar ( const internal::MultibodyTree< symbolic::Expression > &  ) const
overrideprotectedvirtual

Implements ForceElement< T >.

◆ gravity_vector()

const Vector3<double>& gravity_vector ( ) const

Returns the acceleration of the gravity vector in m/s², expressed in the world frame W.

◆ is_enabled()

bool is_enabled ( ModelInstanceIndex  model_instance) const
Returns
true iff gravity is enabled for model_instance.
See also
enable(), disable().
Exceptions
std::exceptionif the model instance is invalid.

◆ operator=() [1/2]

UniformGravityFieldElement& operator= ( UniformGravityFieldElement< T > &&  )
delete

◆ operator=() [2/2]

UniformGravityFieldElement& operator= ( const UniformGravityFieldElement< T > &  )
delete

◆ set_enabled()

void set_enabled ( ModelInstanceIndex  model_instance,
bool  is_enabled 
)

Sets is_enabled() for model_instance to is_enabled.

Exceptions
ifthe parent model is finalized.
std::exceptionif the model instance is invalid.

◆ set_gravity_vector()

void set_gravity_vector ( const Vector3< double > &  g_W)

Sets the acceleration of gravity vector, expressed in the world frame W in m/s².

Member Data Documentation

◆ kDefaultStrength

constexpr double kDefaultStrength = 9.81
static

The strength used by our class's default constructor (i.e., on the earth's surface).

This is an unsigned (positive) value in m/s².


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