Drake
MultibodyForces< T > Class Template Reference

A class to hold a set of forces applied to a MultibodyTree system. More...

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

Public Member Functions

 MultibodyForces (const MultibodyTree< T > &model)
 Constructs a force object to store a set of forces to be applied to model. More...
 
MultibodyForces< T > & SetZero ()
 Sets this to store zero forces (no applied forces). More...
 
int num_bodies () const
 Returns the number of bodies for which this force object applies. More...
 
int num_velocities () const
 Returns the number of generalized velocities for the model to which these forces apply. More...
 
const VectorX< T > & generalized_forces () const
 Returns a constant reference to the vector of generalized forces stored by this forces object. More...
 
VectorX< T > & mutable_generalized_forces ()
 Mutable version of generalized_forces(). More...
 
const std::vector< SpatialForce< T > > & body_forces () const
 Returns a constant reference to the vector of spatial body forces F_BBo_W on each body B in the model, at the body's frame origin Bo, expressed in the world frame W. More...
 
std::vector< SpatialForce< T > > & mutable_body_forces ()
 Mutable version of body_forces(). More...
 
void AddInForces (const MultibodyForces< T > &addend)
 Adds into this the force contribution stored in addend. More...
 
bool CheckHasRightSizeForModel (const MultibodyTree< T > &model) const
 Utility that checks that the forces stored by this object have the proper sizes to represent the set of forces for the given model. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 MultibodyForces (const MultibodyForces &)=default
 
MultibodyForcesoperator= (const MultibodyForces &)=default
 
 MultibodyForces (MultibodyForces &&)=default
 
MultibodyForcesoperator= (MultibodyForces &&)=default
 

Detailed Description

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

A class to hold a set of forces applied to a MultibodyTree system.

Forces can include generalized forces as well as body spatial forces.

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

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

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

Constructor & Destructor Documentation

MultibodyForces ( const MultibodyForces< T > &  )
default
MultibodyForces ( MultibodyForces< T > &&  )
default
MultibodyForces ( const MultibodyTree< T > &  model)
explicit

Constructs a force object to store a set of forces to be applied to model.

Forces are initialized to zero, meaning no forces are applied to model. model must have been already finalized with MultibodyTree::Finalize() or this constructor will abort.

Here is the call graph for this function:

Member Function Documentation

void AddInForces ( const MultibodyForces< T > &  addend)

Adds into this the force contribution stored in addend.

Here is the call graph for this function:

Here is the caller graph for this function:

const std::vector<SpatialForce<T> >& body_forces ( ) const
inline

Returns a constant reference to the vector of spatial body forces F_BBo_W on each body B in the model, at the body's frame origin Bo, expressed in the world frame W.

Note
Entries are ordered by BodyNodeIndex.

Here is the caller graph for this function:

bool CheckHasRightSizeForModel ( const MultibodyTree< T > &  model) const

Utility that checks that the forces stored by this object have the proper sizes to represent the set of forces for the given model.

Returns
true if this forces object has the proper sizes for the given model.

Here is the call graph for this function:

Here is the caller graph for this function:

const VectorX<T>& generalized_forces ( ) const
inline

Returns a constant reference to the vector of generalized forces stored by this forces object.

Here is the caller graph for this function:

std::vector<SpatialForce<T> >& mutable_body_forces ( )
inline

Mutable version of body_forces().

Here is the call graph for this function:

Here is the caller graph for this function:

VectorX<T>& mutable_generalized_forces ( )
inline

Mutable version of generalized_forces().

Here is the caller graph for this function:

int num_bodies ( ) const
inline

Returns the number of bodies for which this force object applies.

Determined at construction from the given model MultibodyTree object.

Here is the caller graph for this function:

int num_velocities ( ) const
inline

Returns the number of generalized velocities for the model to which these forces apply.

The number of generalized forces in a multibody model always equals the number of generalized velocities. Determined at construction from the given model MultibodyTree object.

Here is the caller graph for this function:

MultibodyForces& operator= ( MultibodyForces< T > &&  )
default
MultibodyForces& operator= ( const MultibodyForces< T > &  )
default
MultibodyForces< T > & SetZero ( )

Sets this to store zero forces (no applied forces).

Here is the call graph for this function:

Here is the caller graph for this function:


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