Drake
Drake C++ Documentation
MultibodyForces< T > Class Template Reference

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. MultibodyPlant::CalcGeneralizedForces() can be used to compute the total generalized force, combining generalized_forces() and body_forces().

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

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

Public Member Functions

 MultibodyForces (const internal::MultibodyTreeSystem< T > &plant)
 Constructs a force object to store a set of forces to be applied to the multibody model for plant. More...
 
 MultibodyForces (const internal::MultibodyTree< T > &model)
 (Advanced) Tree overload. More...
 
 MultibodyForces (int nb, int nv)
 Number of bodies and number of generalized velocities overload. More...
 
 ~MultibodyForces ()
 
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
 (Advanced) Returns a constant reference to the vector of generalized forces stored by this forces object. More...
 
VectorX< T > & mutable_generalized_forces ()
 (Advanced) Mutable version of generalized_forces(). More...
 
const std::vector< SpatialForce< T > > & body_forces () const
 (Advanced) 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 ()
 (Advanced) 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 internal::MultibodyTreeSystem< T > &plant) const
 Utility that checks that the forces stored by this object have the proper sizes to represent the set of forces for the given plant. More...
 
bool CheckHasRightSizeForModel (const internal::MultibodyTree< T > &model) const
 (Advanced) Tree overload. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 MultibodyForces (const MultibodyForces &)=default
 
MultibodyForcesoperator= (const MultibodyForces &)=default
 
 MultibodyForces (MultibodyForces &&)=default
 
MultibodyForcesoperator= (MultibodyForces &&)=default
 

Constructor & Destructor Documentation

◆ MultibodyForces() [1/5]

MultibodyForces ( const MultibodyForces< T > &  )
default

◆ MultibodyForces() [2/5]

MultibodyForces ( MultibodyForces< T > &&  )
default

◆ MultibodyForces() [3/5]

MultibodyForces ( const internal::MultibodyTreeSystem< T > &  plant)
explicit

Constructs a force object to store a set of forces to be applied to the multibody model for plant.

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

◆ MultibodyForces() [4/5]

MultibodyForces ( const internal::MultibodyTree< T > &  model)
explicit

(Advanced) Tree overload.

◆ MultibodyForces() [5/5]

MultibodyForces ( int  nb,
int  nv 
)

Number of bodies and number of generalized velocities overload.

This constructor is useful for constructing the MultibodyForces structure before a MultibodyPlant has been constructed.

◆ ~MultibodyForces()

Member Function Documentation

◆ AddInForces()

void AddInForces ( const MultibodyForces< T > &  addend)

Adds into this the force contribution stored in addend.

◆ body_forces()

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

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

◆ CheckHasRightSizeForModel() [1/2]

bool CheckHasRightSizeForModel ( const internal::MultibodyTreeSystem< T > &  plant) const

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

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

◆ CheckHasRightSizeForModel() [2/2]

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

(Advanced) Tree overload.

◆ generalized_forces()

const VectorX<T>& generalized_forces ( ) const

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

◆ mutable_body_forces()

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

(Advanced) Mutable version of body_forces().

◆ mutable_generalized_forces()

VectorX<T>& mutable_generalized_forces ( )

(Advanced) Mutable version of generalized_forces().

◆ num_bodies()

int num_bodies ( ) const

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

Determined at construction from the given model MultibodyTree object.

◆ num_velocities()

int num_velocities ( ) const

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.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ SetZero()

MultibodyForces<T>& SetZero ( )

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


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