Drake
UniformGravityFieldElement< T > Class Template Reference

This ForceElement allows modeling the effect of a uniform gravity field as felt by bodies on the surface of the Earth. More...

#include <multibody/multibody_tree/uniform_gravity_field_element.h>

Inheritance diagram for UniformGravityFieldElement< T >:
[legend]
Collaboration diagram for UniformGravityFieldElement< T >:
[legend]

Public Member Functions

 UniformGravityFieldElement (Vector3< double > g_W)
 Constructs a uniform gravity field element with a strength given by the acceleration of gravity vector g_W, expressed in the world frame W. More...
 
const Vector3< double > & gravity_vector () const
 Returns the acceleration of gravity vector, expressed in the world frame W. More...
 
CalcPotentialEnergy (const MultibodyTreeContext< T > &context, const PositionKinematicsCache< T > &pc) const final
 Calculates the potential energy currently stored given the configuration provided in context. More...
 
CalcConservativePower (const MultibodyTreeContext< T > &context, const PositionKinematicsCache< T > &pc, const VelocityKinematicsCache< T > &vc) const final
 Calculates and returns the power generated by conservative force elements or zero if this force element is non-conservative. More...
 
CalcNonConservativePower (const MultibodyTreeContext< T > &context, const PositionKinematicsCache< T > &pc, const VelocityKinematicsCache< T > &vc) const final
 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
 UniformGravityFieldElement (const UniformGravityFieldElement &)=delete
 
UniformGravityFieldElementoperator= (const UniformGravityFieldElement &)=delete
 
 UniformGravityFieldElement (UniformGravityFieldElement &&)=delete
 
UniformGravityFieldElementoperator= (UniformGravityFieldElement &&)=delete
 
- Public Member Functions inherited from ForceElement< T >
 ForceElement ()
 Default constructor for a generic force element. More...
 
void CalcAndAddForceContribution (const MultibodyTreeContext< T > &context, const PositionKinematicsCache< T > &pc, const VelocityKinematicsCache< T > &vc, std::vector< SpatialForce< T >> *F_B_W_array, EigenPtr< VectorX< T >> tau_array) const
 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 MultibodyTreeContext< T > &context, const PositionKinematicsCache< T > &pc, const VelocityKinematicsCache< T > &vc, std::vector< SpatialForce< T >> *F_B_W, EigenPtr< VectorX< T >> tau) const final
 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 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 MultibodyTree< AutoDiffXd > &tree_clone) const override
 Clones this ForceElement (templated on T) to a mobilizer templated on AutoDiffXd. 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:
// 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().

Detailed Description

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

This ForceElement allows modeling the effect of a uniform gravity field as felt by bodies on the surface of the Earth.

This gravity fields acts on all bodies in the MultibodyTree model.

Template Parameters
TThe scalar type. Must be a valid Eigen scalar.

Instantiated templates for the following kinds of T's are provided:

  • double
  • AutoDiffXd

They are already available to link against in the containing library. No other values for T are currently supported.

Constructor & Destructor Documentation

Constructs a uniform gravity field element with a strength given by the acceleration of gravity vector g_W, expressed in the world frame W.

Member Function Documentation

T CalcConservativePower ( const MultibodyTreeContext< T > &  context,
const PositionKinematicsCache< T > &  pc,
const VelocityKinematicsCache< T > &  vc 
) const
finalvirtual

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

Here is the call graph for this function:

Here is the caller graph for this function:

T CalcNonConservativePower ( const MultibodyTreeContext< T > &  context,
const PositionKinematicsCache< T > &  pc,
const VelocityKinematicsCache< T > &  vc 
) const
finalvirtual

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

Here is the caller graph for this function:

T CalcPotentialEnergy ( const MultibodyTreeContext< T > &  context,
const PositionKinematicsCache< T > &  pc 
) const
finalvirtual

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().
The velocity kinematics vc must have been previously updated with a call to CalcVelocityKinematicsCache().
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 >.

Here is the call graph for this function:

Here is the caller graph for this function:

void DoCalcAndAddForceContribution ( const MultibodyTreeContext< T > &  context,
const PositionKinematicsCache< T > &  pc,
const VelocityKinematicsCache< T > &  vc,
std::vector< SpatialForce< T >> *  F_B_W,
EigenPtr< VectorX< T >>  tau 
) const
finalprotectedvirtual

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 both F_B_W and tau are valid pointers with appropriate sizes already checked by CalcAndAddForceContribution().

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

Here is the call graph for this function:

Here is the caller graph for this function:

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

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

Implements ForceElement< T >.

Here is the call graph for this function:

Here is the caller graph for this function:

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

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

Implements ForceElement< T >.

Here is the call graph for this function:

const Vector3<double>& gravity_vector ( ) const
inline

Returns the acceleration of gravity vector, expressed in the world frame W.

Here is the call graph for this function:

Here is the caller graph for this function:

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

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