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
-
|
| 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...
|
|
| ~UniformGravityFieldElement () override |
|
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...
|
|
T | 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...
|
|
T | 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...
|
|
T | 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...
|
|
|
| UniformGravityFieldElement (const UniformGravityFieldElement &)=delete |
|
UniformGravityFieldElement & | operator= (const UniformGravityFieldElement &)=delete |
|
| UniformGravityFieldElement (UniformGravityFieldElement &&)=delete |
|
UniformGravityFieldElement & | operator= (UniformGravityFieldElement &&)=delete |
|
Public Member Functions inherited from ForceElement< T > |
| ForceElement (ModelInstanceIndex model_instance) |
| Default constructor for a generic force element. More...
|
|
| ~ForceElement () override |
|
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 |
|
ForceElement & | operator= (const ForceElement &)=delete |
|
| ForceElement (ForceElement &&)=delete |
|
ForceElement & | operator= (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 = void> |
const MultibodyPlant< T > & | 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...
|
|
void | DeclareDiscreteState (internal::MultibodyTreeSystem< T > *tree_system) |
| Declares MultibodyTreeSystem discrete states. More...
|
|
void | DeclareCacheEntries (internal::MultibodyTreeSystem< T > *tree_system) |
| (Advanced) Declares all cache entries needed by this element. More...
|
|
bool | is_ephemeral () const |
| Returns true if this MultibodyElement was added during Finalize() rather than something a user added. More...
|
|
void | set_is_ephemeral (bool is_ephemeral) |
| (Internal use only) Sets the is_ephemeral flag to the indicated value. More...
|
|
| MultibodyElement (const MultibodyElement &)=delete |
|
MultibodyElement & | operator= (const MultibodyElement &)=delete |
|
| MultibodyElement (MultibodyElement &&)=delete |
|
MultibodyElement & | operator= (MultibodyElement &&)=delete |
|
|
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 |
|
std::unique_ptr< ForceElement< T > > | DoShallowClone () const override |
| NVI for ShallowClone(). More...
|
|
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...
|
|
template<typename ElementOrdinalType = int64_t> |
ElementOrdinalType | ordinal_impl () const |
| Returns this element's unique ordinal. 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...
|
|
virtual void | DoDeclareDiscreteState (internal::MultibodyTreeSystem< T > *) |
| Implementation of the NVI DeclareDiscreteState(). More...
|
|
virtual void | DoDeclareCacheEntries (internal::MultibodyTreeSystem< T > *) |
| Derived classes must override this method to declare cache entries needed by this element. 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...
|
|
systems::DiscreteStateIndex | DeclareDiscreteState (internal::MultibodyTreeSystem< T > *tree_system, const VectorX< T > &model_value) |
| To be used by MultibodyElement-derived objects when declaring discrete states in their implementation of DoDeclareDiscreteStates(). More...
|
|
systems::CacheEntry & | DeclareCacheEntry (internal::MultibodyTreeSystem< T > *tree_system, std::string description, systems::ValueProducer value_producer, std::set< systems::DependencyTicket > prerequisites_of_calc) |
| To be used by MultibodyElement-derived objects when declaring cache entries in their implementation of DoDeclareCacheEntries(). More...
|
|
bool | has_parent_tree () const |
| Returns true if this multibody element has a parent tree, otherwise false. More...
|
|
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] | context | The 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.