template<typename T>
class drake::multibody::RevoluteSpring< T >
This ForceElement models a torsional spring attached to a RevoluteJoint and applies a torque to that joint.
τ = -k⋅(θ - θ₀)
where θ₀ is the nominal joint position. Note that joint damping exists within the RevoluteJoint itself, and so is not included here.
The k (stiffness) and θ₀ (nominal angle) specified in the constructor are kept as default values. These parameters are stored within the context and can be accessed and set by context dependent getters/setters.
- Template Parameters
-
|
| | RevoluteSpring (const RevoluteJoint< T > &joint, double nominal_angle, double stiffness) |
| | Constructor for a spring attached to the given joint.
|
| | ~RevoluteSpring () override |
| const RevoluteJoint< T > & | joint () const |
| | Returns the joint associated with this spring.
|
| double | default_nominal_angle () const |
| | Returns the default spring reference angle θ₀ in radians.
|
| double | default_stiffness () const |
| | Returns the default stiffness constant k in N⋅m/rad.
|
| const T & | GetNominalAngle (const systems::Context< T > &context) const |
| | Returns the Context dependent nominal angle θ₀ stored as a parameter in context.
|
| void | SetNominalAngle (systems::Context< T > *context, const T &nominal_angle) const |
| | Sets the value of the nominal angle θ₀ for this force element, stored as a parameter in context.
|
| const T & | GetStiffness (const systems::Context< T > &context) const |
| | Returns the Context dependent stiffness coefficient k stored as a parameter in context.
|
| void | SetStiffness (systems::Context< T > *context, const T &stiffness) const |
| | Sets the value of the linear stiffness coefficient k for this force element, stored as a parameter in context.
|
| T | CalcPotentialEnergy (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc) const override |
| | (Advanced) Calculates the potential energy currently stored given the configuration provided in context.
|
| T | CalcConservativePower (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc, const internal::VelocityKinematicsCache< T > &vc) const override |
| | (Advanced) Calculates and returns the power generated by conservative force elements or zero if this force element is non-conservative.
|
| T | CalcNonConservativePower (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc, const internal::VelocityKinematicsCache< T > &vc) const override |
| | (Advanced) Calculates the rate at which mechanical energy is being generated (positive) or dissipated (negative) other than by conversion between potential and kinetic energy.
|
| | RevoluteSpring (const RevoluteSpring &)=delete |
| RevoluteSpring & | operator= (const RevoluteSpring &)=delete |
| | RevoluteSpring (RevoluteSpring &&)=delete |
| RevoluteSpring & | operator= (RevoluteSpring &&)=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 override |
| | 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 > |
| 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.
|