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

Detailed Description

template<typename T>
class drake::multibody::LinearSpringDamper< T >

This ForceElement models a spring-damper attached between two points on two different bodies.

Given a point P on a body A and a point Q on a body B with positions p_AP and p_BQ, respectively, this spring-damper applies equal and opposite forces on bodies A and B according to:

  f_AP = (k⋅(ℓ - ℓ₀) + c⋅dℓ/dt)⋅r̂
  f_BQ = -f_AP

where ℓ = ‖p_WQ - p_WP‖ is the current length of the spring, dℓ/dt its rate of change, r̂ = (p_WQ - p_WP) / ℓ is the normalized vector from P to Q, ℓ₀ is the free length of the spring and k and c are the stiffness and damping of the spring-damper, respectively. This ForceElement is meant to model finite free length springs attached between two points. In this typical arrangement springs are usually pre-loaded, meaning they apply a non-zero spring force in the static configuration of the system. Thus, neither the free length ℓ₀ nor the current length ℓ of the spring can ever be zero. The length of the spring approaching zero would incur in a non-physical configuration and therefore this element throws a std::runtime_error exception in that case. Note that:

  • The applied force is always along the line connecting points P and Q.
  • Damping always dissipates energy.
  • Forces on bodies A and B are equal and opposite according to Newton's third law.
Template Parameters
TThe scalar type, which must be one of the default scalars.

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

Public Member Functions

 LinearSpringDamper (const RigidBody< T > &bodyA, const Vector3< double > &p_AP, const RigidBody< T > &bodyB, const Vector3< double > &p_BQ, double free_length, double stiffness, double damping)
 Constructor for a spring-damper between a point P on bodyA and a point Q on bodyB. More...
 
 ~LinearSpringDamper () override
 
const RigidBody< T > & bodyA () const
 
const RigidBody< T > & bodyB () const
 
const Vector3< doublep_AP () const
 The position p_AP of point P on body A as measured and expressed in body frame A. More...
 
const Vector3< doublep_BQ () const
 The position p_BQ of point Q on body B as measured and expressed in body frame B. More...
 
double free_length () const
 
double stiffness () const
 
double damping () 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
 LinearSpringDamper (const LinearSpringDamper &)=delete
 
LinearSpringDamperoperator= (const LinearSpringDamper &)=delete
 
 LinearSpringDamper (LinearSpringDamper &&)=delete
 
LinearSpringDamperoperator= (LinearSpringDamper &&)=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
 
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
 

Protected Member Functions

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

◆ LinearSpringDamper() [1/3]

LinearSpringDamper ( const LinearSpringDamper< T > &  )
delete

◆ LinearSpringDamper() [2/3]

LinearSpringDamper ( LinearSpringDamper< T > &&  )
delete

◆ LinearSpringDamper() [3/3]

LinearSpringDamper ( const RigidBody< T > &  bodyA,
const Vector3< double > &  p_AP,
const RigidBody< T > &  bodyB,
const Vector3< double > &  p_BQ,
double  free_length,
double  stiffness,
double  damping 
)

Constructor for a spring-damper between a point P on bodyA and a point Q on bodyB.

Point P is defined by its position p_AP as measured and expressed in the body frame A and similarly, point Q is defined by its position p_BQ as measured and expressed in body frame B. The remaining parameters define:

Parameters
[in]free_lengthThe free length of the spring ℓ₀, in meters, at which the spring applies no forces. Since this force element is meant to model finite length springs, ℓ₀ must be strictly positive.
[in]stiffnessThe stiffness k of the spring in N/m. It must be non-negative.
[in]dampingThe damping c of the damper in N⋅s/m. It must be non-negative. Refer to this class's documentation for further details.
Exceptions
std::exceptionif free_length is negative or zero.
std::exceptionif stiffness is negative.
std::exceptionif damping is negative.

◆ ~LinearSpringDamper()

~LinearSpringDamper ( )
override

Member Function Documentation

◆ bodyA()

const RigidBody<T>& bodyA ( ) const

◆ bodyB()

const RigidBody<T>& bodyB ( ) const

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

◆ damping()

double damping ( ) const

◆ DoCalcAndAddForceContribution()

void DoCalcAndAddForceContribution ( const systems::Context< T > &  context,
const internal::PositionKinematicsCache< T > &  pc,
const internal::VelocityKinematicsCache< T > &  vc,
MultibodyForces< T > *  forces 
) const
overrideprotectedvirtual

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.

Refer to the documentation for CalcAndAddForceContribution() for details describing the purpose and parameters of this method. It assumes forces to be a valid pointer to a MultibodyForces object compatible with the MultibodyTree model owning this force element.

Precondition
The position kinematics pc must have been previously updated with a call to CalcPositionKinematicsCache().
The velocity kinematics vc must have been previously updated with a call to CalcVelocityKinematicsCache().

Implements ForceElement< T >.

◆ DoCloneToScalar() [1/3]

std::unique_ptr<ForceElement<double> > DoCloneToScalar ( const internal::MultibodyTree< double > &  tree_clone) const
overrideprotectedvirtual

Clones this ForceElement (templated on T) to a mobilizer templated on double.

Implements ForceElement< T >.

◆ DoCloneToScalar() [2/3]

std::unique_ptr<ForceElement<AutoDiffXd> > DoCloneToScalar ( const internal::MultibodyTree< AutoDiffXd > &  tree_clone) const
overrideprotectedvirtual

Clones this ForceElement (templated on T) to a mobilizer templated on AutoDiffXd.

Implements ForceElement< T >.

◆ DoCloneToScalar() [3/3]

std::unique_ptr<ForceElement<symbolic::Expression> > DoCloneToScalar ( const internal::MultibodyTree< symbolic::Expression > &  ) const
overrideprotectedvirtual

Implements ForceElement< T >.

◆ free_length()

double free_length ( ) const

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ p_AP()

const Vector3<double> p_AP ( ) const

The position p_AP of point P on body A as measured and expressed in body frame A.

◆ p_BQ()

const Vector3<double> p_BQ ( ) const

The position p_BQ of point Q on body B as measured and expressed in body frame B.

◆ stiffness()

double stiffness ( ) const

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