Drake
Drake C++ Documentation
ForceElement< T > Class Template Referenceabstract

Detailed Description

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

A ForceElement allows modeling state and time dependent forces in a MultibodyTree model.

Examples of such forces are springs, dampers, drag and gravity. Forces that depend on accelerations such as virtual mass cannot be modeled with a ForceElement. This abstract class provides an API that all force elements subclasses must implement in order to be fully defined. These are:

Template Parameters
TThe scalar type, which must be one of the default scalars.

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

Public Member Functions

 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...
 
Does not allow copy, move, or assignment
 ForceElement (const ForceElement &)=delete
 
ForceElementoperator= (const ForceElement &)=delete
 
 ForceElement (ForceElement &&)=delete
 
ForceElementoperator= (ForceElement &&)=delete
 
Methods to track the energy budget.

The methods in this group are used to track the transfer of energy within a MultibodyTree model.

This methods are pure virtual and subclasses must provide an implementation. Conservative force elements must implement CalcPotentialEnergy() in order to track the potential energy stored in force elements. In addition, conservative force elements must implement the rate of change of this potential energy in CalcConservativePower(). Non-conservative force elements need to implement the rate of change, power, at which they either generate or dissipate energy in the system in CalcNonConservativePower(). Note that a force element may have both conservative and non-conservative contributions, such as a spring-damper element for instance. All of these methods have the same signature. Refer to the documentation for CalcPotentialEnergy() for a detailed description of the input arguments of the methods in this group.

virtual T CalcPotentialEnergy (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc) const =0
 (Advanced) Calculates the potential energy currently stored given the configuration provided in context. More...
 
virtual T CalcConservativePower (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc, const internal::VelocityKinematicsCache< T > &vc) const =0
 (Advanced) Calculates and returns the power generated by conservative force elements or zero if this force element is non-conservative. More...
 
virtual T CalcNonConservativePower (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc, const internal::VelocityKinematicsCache< T > &vc) const =0
 (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...
 
- 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

virtual void DoCalcAndAddForceContribution (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc, const internal::VelocityKinematicsCache< T > &vc, MultibodyForces< T > *forces) const =0
 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...
 
virtual void DoDeclareForceElementParameters (internal::MultibodyTreeSystem< T > *)
 Called by DoDeclareParameters(). More...
 
virtual void DoSetDefaultForceElementParameters (systems::Parameters< T > *) const
 Called by DoSetDefaultParameters(). More...
 
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 ForceElement<T> {
public:
// Class's constructor.
SpringElement(
const RigidBody<T>& body1, const RigidBody<T>& body2,
double stiffness);
// Get the first body to which this spring is connected.
const RigidBody<T>& get_body1() const;
// Get the second body to which this spring is connected.
const RigidBody<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 RigidBody<ToScalar>& body1_clone =
tree_clone.get_variant(get_body1());
const RigidBody<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().

virtual std::unique_ptr< ForceElement< double > > DoCloneToScalar (const internal::MultibodyTree< double > &tree_clone) const =0
 Clones this ForceElement (templated on T) to a mobilizer templated on double. More...
 
virtual std::unique_ptr< ForceElement< AutoDiffXd > > DoCloneToScalar (const internal::MultibodyTree< AutoDiffXd > &tree_clone) const =0
 Clones this ForceElement (templated on T) to a mobilizer templated on AutoDiffXd. More...
 
virtual std::unique_ptr< ForceElement< symbolic::Expression > > DoCloneToScalar (const internal::MultibodyTree< symbolic::Expression > &) const =0
 
- 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

◆ ForceElement() [1/3]

ForceElement ( const ForceElement< T > &  )
delete

◆ ForceElement() [2/3]

ForceElement ( ForceElement< T > &&  )
delete

◆ ForceElement() [3/3]

ForceElement ( ModelInstanceIndex  model_instance)
explicit

Default constructor for a generic force element.

◆ ~ForceElement()

~ForceElement ( )
override

Member Function Documentation

◆ CalcAndAddForceContribution()

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.

Depending on their model, different force elements may write into the array of spatial forces F_B_W or the array of generalized forces tau.

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.
[in]vcA velocity kinematics cache object already updated to be in sync with context.
[out]forcesA pointer to a valid, non nullptr, multibody forces object. On output this force element adds its contribution into forces. This method will abort if the forces pointer is null or if the forces object is not compatible with this MultibodyTree, see MultibodyForces::CheckInvariants().
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().

◆ CalcConservativePower()

virtual T CalcConservativePower ( const systems::Context< T > &  context,
const internal::PositionKinematicsCache< T > &  pc,
const internal::VelocityKinematicsCache< T > &  vc 
) const
pure virtual

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

Implemented in DoorHinge< T >, UniformGravityFieldElement< T >, LinearSpringDamper< T >, PrismaticSpring< T >, and RevoluteSpring< T >.

◆ CalcNonConservativePower()

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

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

Implemented in DoorHinge< T >, UniformGravityFieldElement< T >, LinearSpringDamper< T >, PrismaticSpring< T >, and RevoluteSpring< T >.

◆ CalcPotentialEnergy()

virtual T CalcPotentialEnergy ( const systems::Context< T > &  context,
const internal::PositionKinematicsCache< T > &  pc 
) const
pure virtual

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

Implemented in DoorHinge< T >, UniformGravityFieldElement< T >, LinearSpringDamper< T >, PrismaticSpring< T >, and RevoluteSpring< T >.

◆ DoCalcAndAddForceContribution()

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

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

Implemented in DoorHinge< T >, UniformGravityFieldElement< T >, LinearSpringDamper< T >, and RevoluteSpring< T >.

◆ DoCloneToScalar() [1/3]

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

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

Implemented in DoorHinge< T >, UniformGravityFieldElement< T >, LinearSpringDamper< T >, and RevoluteSpring< T >.

◆ DoCloneToScalar() [2/3]

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

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

Implemented in DoorHinge< T >, UniformGravityFieldElement< T >, LinearSpringDamper< T >, and RevoluteSpring< T >.

◆ DoCloneToScalar() [3/3]

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

◆ DoDeclareForceElementParameters()

virtual void DoDeclareForceElementParameters ( internal::MultibodyTreeSystem< T > *  )
protectedvirtual

Called by DoDeclareParameters().

Derived classes may choose to override to declare their sub-class specific parameters.

◆ DoSetDefaultForceElementParameters()

virtual void DoSetDefaultForceElementParameters ( systems::Parameters< T > *  ) const
protectedvirtual

Called by DoSetDefaultParameters().

Derived classes may choose to override to set their sub-class specific parameters.

◆ index()

ForceElementIndex index ( ) const

Returns this element's unique index.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

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