Drake
RevoluteSpring< T > Class Template Referencefinal

Detailed Description

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.

Template Parameters
TMust be one of drake's default scalar types.

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

Public Member Functions

 RevoluteSpring (const RevoluteJoint< T > &joint, double nominal_angle, double stiffness)
 Constructor for a spring attached to the given joint. More...
 
const RevoluteJoint< T > & joint () const
 
double nominal_angle () 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
 RevoluteSpring (const RevoluteSpring &)=delete
 
RevoluteSpringoperator= (const RevoluteSpring &)=delete
 
 RevoluteSpring (RevoluteSpring &&)=delete
 
RevoluteSpringoperator= (RevoluteSpring &&)=delete
 
- Public Member Functions inherited from ForceElement< T >
 ForceElement (ModelInstanceIndex model_instance)
 Default constructor for a generic force element. 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
 

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
 
Methods to make a clone templated on different scalar types.

Specific force element subclasses must implement these to support scalar conversion to other types.

These methods are only called from MultibodyTree::CloneToScalar(); users must not call these explicitly since there is no external mechanism to ensure the argument tree_clone is in a valid stage of cloning. In contrast, MultibodyTree::CloneToScalar() guarantees that by when ForceElement::CloneToScalar() is called, all Body, Frame and Mobilizer objects in the original tree (templated on T) to which this ForceElement<T> belongs, have a corresponding clone in the cloned tree (argument tree_clone for these methods). Therefore, implementations of ForceElement::DoCloneToScalar() can retrieve clones from tree_clone as needed. Consider the following example for a SpringElement<T> used to model an elastic spring between two bodies:

template <typename T>
class SpringElement {
public:
// Class's constructor.
SpringElement(
const Body<T>& body1, const Body<T>& body2, double stiffness);
// Get the first body to which this spring is connected.
const Body<T>& get_body1() const;
// Get the second body to which this spring is connected.
const Body<T>& get_body2() const;
// Get the spring stiffness constant.
double get_stiffness() const;
protected:
// Implementation of the scalar conversion from T to double.
std::unique_ptr<ForceElement<double>> DoCloneToScalar(
const MultibodyTree<double>& tree_clone) const) {
const Body<ToScalar>& body1_clone =
tree_clone.get_variant(get_body1());
const Body<ToScalar>& body2_clone =
tree_clone.get_variant(get_body2());
return std::make_unique<SpringElement<double>>(
body1_clone, body2_clone, get_stiffness());
}

MultibodyTree::get_variant() methods are available to retrieve cloned variants from tree_clone, and are overloaded on different element types.

For examples on how a MultibodyTree model can be converted to other scalar types, please refer to the documentation for MultibodyTree::CloneToScalar().

Constructor & Destructor Documentation

◆ RevoluteSpring() [1/3]

RevoluteSpring ( const RevoluteSpring< T > &  )
delete

◆ RevoluteSpring() [2/3]

RevoluteSpring ( RevoluteSpring< T > &&  )
delete

◆ RevoluteSpring() [3/3]

RevoluteSpring ( const RevoluteJoint< T > &  joint,
double  nominal_angle,
double  stiffness 
)

Constructor for a spring attached to the given joint.

Parameters
[in]nominal_angleThe nominal angle of the spring θ₀, in radians, at which the spring applies no moment.
[in]stiffnessThe stiffness k of the spring in N⋅m/rad.
Exceptions
std::exceptionif stiffness is 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 >.

◆ 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 > &  tree_clone) const
overrideprotectedvirtual

Implements ForceElement< T >.

◆ joint()

const RevoluteJoint<T>& joint ( ) const

◆ nominal_angle()

double nominal_angle ( ) const

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ stiffness()

double stiffness ( ) const

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