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
-
|
| 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< double > | p_AP () const |
| The position p_AP of point P on body A as measured and expressed in body frame A. More...
|
|
const Vector3< double > | p_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 |
|
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 . More...
|
|
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. More...
|
|
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. More...
|
|
|
| LinearSpringDamper (const LinearSpringDamper &)=delete |
|
LinearSpringDamper & | operator= (const LinearSpringDamper &)=delete |
|
| LinearSpringDamper (LinearSpringDamper &&)=delete |
|
LinearSpringDamper & | operator= (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 |
|
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. More...
|
|
template<typename = void> |
const MultibodyPlant< T > & | 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...
|
|
void | DeclareDiscreteState (internal::MultibodyTreeSystem< T > *tree_system) |
| Declares MultibodyTreeSystem discrete states. More...
|
|
void | DeclareCacheEntries (internal::MultibodyTreeSystem< T > *tree_system) |
| (Advanced) Declares all cache entries needed by this element. More...
|
|
bool | is_ephemeral () const |
| Returns true if this MultibodyElement was added during Finalize() rather than something a user added. More...
|
|
void | set_is_ephemeral (bool is_ephemeral) |
| (Internal use only) Sets the is_ephemeral flag to the indicated value. More...
|
|
| 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. 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 |
|
std::unique_ptr< ForceElement< T > > | DoShallowClone () const override |
| NVI for ShallowClone(). More...
|
|
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...
|
|
template<typename ElementOrdinalType = int64_t> |
ElementOrdinalType | 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...
|
|
virtual void | DoDeclareDiscreteState (internal::MultibodyTreeSystem< T > *) |
| Implementation of the NVI DeclareDiscreteState(). More...
|
|
virtual void | DoDeclareCacheEntries (internal::MultibodyTreeSystem< T > *) |
| Derived classes must override this method to declare cache entries needed by this element. 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...
|
|
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(). More...
|
|
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(). More...
|
|
bool | has_parent_tree () const |
| Returns true if this multibody element has a parent tree, otherwise false. More...
|
|