template<typename T>
class drake::multibody::PrismaticSpring< T >
This ForceElement models a linear spring attached to a PrismaticJoint and applies a force to that joint according to.
f = -k⋅(x - x₀)
where x₀ is the nominal (zero spring force) position in meters, x is the joint position in meters, f is the spring force in Newtons and k is the spring constant in N/m. Note that joint damping exists within the PrismaticJoint itself, and so is not included here.
- Note
- This is different from the LinearSpringDamper: this PrismaticSpring is associated with a joint, while the LinearSpringDamper connects two bodies.
- Template Parameters
-
|
| | PrismaticSpring (const PrismaticJoint< T > &joint, double nominal_position, double stiffness) |
| | Constructor for a linear spring attached to the given prismatic joint.
|
| | ~PrismaticSpring () override |
| const PrismaticJoint< T > & | joint () const |
| | Returns the joint associated with this spring.
|
| double | nominal_position () const |
| double | stiffness () const |
| 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.
|
| | PrismaticSpring (const PrismaticSpring &)=delete |
| PrismaticSpring & | operator= (const PrismaticSpring &)=delete |
| | PrismaticSpring (PrismaticSpring &&)=delete |
| PrismaticSpring & | operator= (PrismaticSpring &&)=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 |
template<typename T>
| T CalcConservativePower |
( |
const systems::Context< T > & | context, |
|
|
const internal::PositionKinematicsCache< T > & | pc, |
|
|
const internal::VelocityKinematicsCache< T > & | vc ) const |
|
overridevirtual |
(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 >.