Drake
Drake C++ Documentation
PrismaticSpring< T > Class Template Referencefinal

Detailed Description

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
TThe scalar type, which must be one of the default scalars.

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

Public Member Functions

 PrismaticSpring (const PrismaticJoint< T > &joint, double nominal_position, double stiffness)
 Constructor for a linear spring attached to the given prismatic joint. More...
 
const PrismaticJoint< T > & joint () const
 
double nominal_position () const
 
double stiffness () const
 
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. More...
 
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. More...
 
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. More...
 
Does not allow copy, move, or assignment
 PrismaticSpring (const PrismaticSpring &)=delete
 
PrismaticSpringoperator= (const PrismaticSpring &)=delete
 
 PrismaticSpring (PrismaticSpring &&)=delete
 
PrismaticSpringoperator= (PrismaticSpring &&)=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
 

Friends

template<typename U >
class PrismaticSpring
 

Additional Inherited Members

- 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

◆ PrismaticSpring() [1/3]

PrismaticSpring ( const PrismaticSpring< T > &  )
delete

◆ PrismaticSpring() [2/3]

PrismaticSpring ( PrismaticSpring< T > &&  )
delete

◆ PrismaticSpring() [3/3]

PrismaticSpring ( const PrismaticJoint< T > &  joint,
double  nominal_position,
double  stiffness 
)

Constructor for a linear spring attached to the given prismatic joint.

Parameters
[in]nominal_positionThe nominal position of the spring x₀, in meters, at which the spring applies no force. This is measured the same way as the generalized position of the prismatic joint.
[in]stiffnessThe stiffness k of the spring in N/m.
Exceptions
std::exceptionif stiffness is (strictly) negative.

Member Function Documentation

◆ CalcConservativePower()

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 >.

◆ CalcNonConservativePower()

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

(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
overridevirtual

(Advanced) Calculates the potential energy currently stored given the configuration provided in context.

Non-conservative force elements will return zero.

Parameters
[in]contextThe context containing the state of the MultibodyTree model.
[in]pcA position kinematics cache object already updated to be in sync with context.
Precondition
The position kinematics pc must have been previously updated with a call to CalcPositionKinematicsCache().
Returns
For conservative force models, the potential energy stored by this force element. For non-conservative force models, zero.
See also
CalcConservativePower()

Implements ForceElement< T >.

◆ joint()

const PrismaticJoint<T>& joint ( ) const

◆ nominal_position()

double nominal_position ( ) const

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ stiffness()

double stiffness ( ) const

Friends And Related Function Documentation

◆ PrismaticSpring

friend class PrismaticSpring
friend

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