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 or elsewhere.
This gravity field acts on all bodies in the MultibodyPlant except those whose ModelInstance has been explicitly excluded.
- Template Parameters
-
|
| | UniformGravityFieldElement () |
| | Constructs a uniform gravity field element with a default strength (on the Earth's surface) and direction (-z).
|
| | UniformGravityFieldElement (Vector3< double > g_W) |
| | Constructs a uniform gravity field element with a strength and direction given by the gravity acceleration vector g_W, expressed in the world frame W.
|
| | UniformGravityFieldElement (Vector3< double > g_W, std::set< ModelInstanceIndex > disabled_model_instances) |
| | Constructs a uniform gravity field element with a strength and direction given by the gravity acceleration vector g_W, expressed in the world frame W.
|
| | ~UniformGravityFieldElement () override |
| const Vector3< double > & | gravity_vector () const |
| | Returns the acceleration of gravity vector in m/s², expressed in the world frame W.
|
| void | set_gravity_vector (const Vector3< double > &g_W) |
| | Sets the gravity acceleration vector (in m/s²), expressed in the world frame W.
|
| bool | is_enabled (ModelInstanceIndex model_instance) const |
| | Checks whether gravity is enabled for a given model instance.
|
| void | set_enabled (ModelInstanceIndex model_instance, bool is_enabled) |
| | Enables or disables gravity for a given model_instance.
|
| 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.
|
| T | CalcPotentialEnergy (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc) const final |
| | Computes the total gravitational potential energy of all bodies in this MultibodyPlant except those whose model instance has been explicitly excluded from gravity.
|
| T | CalcConservativePower (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc, const internal::VelocityKinematicsCache< T > &vc) const final |
| | Returns gravitational power acting on the system.
|
| T | CalcNonConservativePower (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc, const internal::VelocityKinematicsCache< T > &vc) const final |
| | Returns zero always since gravity is conservative.
|
| | 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.
|
| | ~ForceElement () override |
| ForceElementIndex | index () const |
| | Returns this element's unique index.
|
| 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.
|
| | 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.
|
| template<typename = void> |
| const MultibodyPlant< T > & | GetParentPlant () const |
| | Returns the MultibodyPlant that owns this MultibodyElement.
|
| void | DeclareParameters (internal::MultibodyTreeSystem< T > *tree_system) |
| | Declares MultibodyTreeSystem Parameters at MultibodyTreeSystem::Finalize() time.
|
| void | SetDefaultParameters (systems::Parameters< T > *parameters) const |
| | Sets default values of parameters belonging to each MultibodyElement in parameters at a call to MultibodyTreeSystem::SetDefaultParameters().
|
| void | DeclareDiscreteState (internal::MultibodyTreeSystem< T > *tree_system) |
| | Declares MultibodyTreeSystem discrete states.
|
| void | DeclareCacheEntries (internal::MultibodyTreeSystem< T > *tree_system) |
| | (Advanced) Declares all cache entries needed by this element.
|
| bool | is_ephemeral () const |
| | Returns true if this MultibodyElement was added during Finalize() rather than something a user added.
|
| void | set_is_ephemeral (bool is_ephemeral) |
| | (Internal use only) Sets the is_ephemeral flag to the indicated value.
|
| | 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.
|
| 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.
|
| 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.
|
| 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().
|
| Protected Member Functions inherited from ForceElement< T > |
| virtual void | DoDeclareForceElementParameters (internal::MultibodyTreeSystem< T > *) |
| | Called by DoDeclareParameters().
|
| virtual void | DoSetDefaultForceElementParameters (systems::Parameters< T > *) const |
| | Called by DoSetDefaultParameters().
|
| 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.
|
| | MultibodyElement (ModelInstanceIndex model_instance) |
| | Constructor which allows specifying a model instance.
|
| | MultibodyElement (ModelInstanceIndex model_instance, int64_t index) |
| | Both the model instance and element index are specified.
|
| template<typename ElementIndexType> |
| ElementIndexType | index_impl () const |
| | Returns this element's unique index.
|
| template<typename ElementOrdinalType = int64_t> |
| ElementOrdinalType | ordinal_impl () const |
| | Returns this element's unique ordinal.
|
| const internal::MultibodyTree< T > & | get_parent_tree () const |
| | Returns a constant reference to the parent MultibodyTree that owns this element.
|
| const internal::MultibodyTreeSystem< T > & | GetParentTreeSystem () const |
| | Returns a constant reference to the parent MultibodyTreeSystem that owns the parent MultibodyTree that owns this element.
|
| void | SetTopology () |
| | (Internal use only) Gives MultibodyElement-derived objects the opportunity to set data members that depend on topology and coordinate assignments having been finalized.
|
| virtual void | DoDeclareDiscreteState (internal::MultibodyTreeSystem< T > *) |
| | Implementation of the NVI DeclareDiscreteState().
|
| virtual void | DoDeclareCacheEntries (internal::MultibodyTreeSystem< T > *) |
| | Derived classes must override this method to declare cache entries needed by this element.
|
| 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().
|
| 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().
|
| 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().
|
| 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().
|
| bool | has_parent_tree () const |
| | Returns true if this multibody element has a parent tree, otherwise false.
|