Drake
Body< T > Class Template Referenceabstract

Detailed Description

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

Body provides the general abstraction of a body with an API that makes no assumption about whether a body is rigid or deformable and neither does it make any assumptions about the underlying physical model or approximation.

As an element or component of a MultibodyTree, a body is a MultibodyTreeElement, and therefore it has a unique index of type BodyIndex within the multibody tree it belongs to.

A Body contains a unique BodyFrame; see BodyFrame class documentation for more information.

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

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

Public Member Functions

 Body (const std::string &name, ModelInstanceIndex model_instance, double default_mass)
 Creates a Body named name in model instance model_instance with a given default_mass and a BodyFrame associated with it. More...
 
const std::string & name () const
 Gets the name associated with this body. More...
 
virtual int get_num_flexible_positions () const =0
 Returns the number of generalized positions q describing flexible deformations for this body. More...
 
virtual int get_num_flexible_velocities () const =0
 Returns the number of generalized velocities v describing flexible deformations for this body. More...
 
const BodyFrame< T > & body_frame () const
 Returns a const reference to the associated BodyFrame. More...
 
internal::BodyNodeIndex node_index () const
 (Advanced) Returns the index of the node in the underlying tree structure of the parent MultibodyTree to which this body belongs. More...
 
bool is_floating () const
 (Advanced) Returns true if this body is granted 6-dofs by a Mobilizer. More...
 
bool has_quaternion_dofs () const
 (Advanced) If true, this body is a floating body modeled with a quaternion floating mobilizer. More...
 
int floating_positions_start () const
 (Advanced) For floating bodies (see is_floating()) this method returns the index of the first generalized position in the state vector for a MultibodyPlant model. More...
 
int floating_velocities_start () const
 (Advanced) For floating bodies (see is_floating()) this method returns the index of the first generalized velocity in the state vector for a MultibodyPlant model. More...
 
double get_default_mass () const
 Returns the default mass (not Context dependent) for this body. More...
 
virtual T get_mass (const systems::Context< T > &context) const =0
 (Advanced) Returns the mass of this body stored in context. More...
 
virtual const Vector3< T > CalcCenterOfMassInBodyFrame (const systems::Context< T > &context) const =0
 (Advanced) Computes the center of mass p_BoBcm_B (or p_Bcm for short) of this body measured from this body's frame origin Bo and expressed in the body frame B. More...
 
virtual SpatialInertia< T > CalcSpatialInertiaInBodyFrame (const systems::Context< T > &context) const =0
 (Advanced) Computes the SpatialInertia I_BBo_B of this body about its frame origin Bo (not necessarily its center of mass) and expressed in its body frame B. More...
 
const math::RigidTransform< T > & EvalPoseInWorld (const systems::Context< T > &context) const
 Returns the pose X_WB of this body B in the world frame W as a function of the state of the model stored in context. More...
 
const SpatialVelocity< T > & EvalSpatialVelocityInWorld (const systems::Context< T > &context) const
 Returns the spatial velocity V_WB of this body B in the world frame W as a function of the state of the model stored in context. More...
 
const SpatialForce< T > & GetForceInWorld (const systems::Context< T > &, const MultibodyForces< T > &forces) const
 Gets the sptatial force on this body B from forces as F_BBo_W: applied at body B's origin Bo and expressed in world world frame W. More...
 
void AddInForceInWorld (const systems::Context< T > &, const SpatialForce< T > &F_Bo_W, MultibodyForces< T > *forces) const
 Adds the spatial force on this body B, applied at body B's origin Bo and expressed in the world frame W into forces. More...
 
void AddInForce (const systems::Context< T > &context, const Vector3< T > &p_BP_E, const SpatialForce< T > &F_Bp_E, const Frame< T > &frame_E, MultibodyForces< T > *forces) const
 Adds the spatial force on this body B, applied at point P and expressed in a frame E into forces. More...
 
template<typename ToScalar >
std::unique_ptr< Body< ToScalar > > CloneToScalar (const internal::MultibodyTree< ToScalar > &tree_clone) const
 NVI (Non-Virtual Interface) to DoCloneToScalar() templated on the scalar type of the new clone to be created. More...
 
Does not allow copy, move, or assignment
 Body (const Body &)=delete
 
Bodyoperator= (const Body &)=delete
 
 Body (Body &&)=delete
 
Bodyoperator= (Body &&)=delete
 

Protected Member Functions

Methods to make a clone templated on different scalar types.

These methods are meant to be called by MultibodyTree::CloneToScalar() when making a clone of the entire tree or a new instance templated on a different scalar type.

The only const argument to these methods is the new MultibodyTree clone under construction. Specific Body subclasses might specify a number of prerequisites on the cloned tree and therefore require it to be at a given state of cloning (for instance requiring that the cloned tree already contains all the frames in the world as in the original tree.) See MultibodyTree::CloneToScalar() for a list of prerequisites that are guaranteed to be satisfied during the cloning process.

virtual std::unique_ptr< Body< double > > DoCloneToScalar (const internal::MultibodyTree< double > &tree_clone) const =0
 Clones this Body (templated on T) to a body templated on double. More...
 
virtual std::unique_ptr< Body< AutoDiffXd > > DoCloneToScalar (const internal::MultibodyTree< AutoDiffXd > &tree_clone) const =0
 Clones this Body (templated on T) to a body templated on AutoDiffXd. More...
 
virtual std::unique_ptr< Body< symbolic::Expression > > DoCloneToScalar (const internal::MultibodyTree< symbolic::Expression > &) const =0
 Clones this Body (templated on T) to a body templated on Expression. More...
 

Friends

class internal::BodyAttorney< T >
 

Constructor & Destructor Documentation

◆ Body() [1/3]

Body ( const Body< T > &  )
delete

◆ Body() [2/3]

Body ( Body< T > &&  )
delete

◆ Body() [3/3]

Body ( const std::string &  name,
ModelInstanceIndex  model_instance,
double  default_mass 
)

Creates a Body named name in model instance model_instance with a given default_mass and a BodyFrame associated with it.

Member Function Documentation

◆ AddInForce()

void AddInForce ( const systems::Context< T > &  context,
const Vector3< T > &  p_BP_E,
const SpatialForce< T > &  F_Bp_E,
const Frame< T > &  frame_E,
MultibodyForces< T > *  forces 
) const

Adds the spatial force on this body B, applied at point P and expressed in a frame E into forces.

Parameters
[in]contextThe context containing the current state of the model.
[in]p_BP_EThe position of point P in B, expressed in a frame E.
[in]F_Bp_EThe spatial force to be applied on body B at point P, expressed in frame E.
[in]frame_EThe expressed-in frame E.
[out]forcesA multibody forces objects that on output will have F_Bp_E added.
Exceptions
std::exceptionif forces is nullptr or if it is not consistent with the model to which this body belongs.

◆ AddInForceInWorld()

void AddInForceInWorld ( const systems::Context< T > &  ,
const SpatialForce< T > &  F_Bo_W,
MultibodyForces< T > *  forces 
) const

Adds the spatial force on this body B, applied at body B's origin Bo and expressed in the world frame W into forces.

◆ body_frame()

const BodyFrame<T>& body_frame ( ) const

Returns a const reference to the associated BodyFrame.

◆ CalcCenterOfMassInBodyFrame()

virtual const Vector3<T> CalcCenterOfMassInBodyFrame ( const systems::Context< T > &  context) const
pure virtual

(Advanced) Computes the center of mass p_BoBcm_B (or p_Bcm for short) of this body measured from this body's frame origin Bo and expressed in the body frame B.

Implemented in RigidBody< T >, RigidBody< double >, and RigidBody< AutoDiffXd >.

◆ CalcSpatialInertiaInBodyFrame()

virtual SpatialInertia<T> CalcSpatialInertiaInBodyFrame ( const systems::Context< T > &  context) const
pure virtual

(Advanced) Computes the SpatialInertia I_BBo_B of this body about its frame origin Bo (not necessarily its center of mass) and expressed in its body frame B.

In general, the spatial inertia of a body is a function of state. Consider for instance the case of a flexible body for which its spatial inertia in the body frame depends on the generalized coordinates describing its state of deformation. As a particular case, the spatial inertia of a RigidBody in its body frame is constant.

Implemented in RigidBody< T >, RigidBody< double >, and RigidBody< AutoDiffXd >.

◆ CloneToScalar()

std::unique_ptr<Body<ToScalar> > CloneToScalar ( const internal::MultibodyTree< ToScalar > &  tree_clone) const

NVI (Non-Virtual Interface) to DoCloneToScalar() templated on the scalar type of the new clone to be created.

This method is mostly intended to be called by MultibodyTree::CloneToScalar(). Most users should not call this clone method directly but rather clone the entire parent MultibodyTree if needed.

See also
MultibodyTree::CloneToScalar()

◆ DoCloneToScalar() [1/3]

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

Clones this Body (templated on T) to a body templated on double.

Implemented in RigidBody< T >, RigidBody< double >, and RigidBody< AutoDiffXd >.

◆ DoCloneToScalar() [2/3]

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

Clones this Body (templated on T) to a body templated on AutoDiffXd.

Implemented in RigidBody< T >, RigidBody< double >, and RigidBody< AutoDiffXd >.

◆ DoCloneToScalar() [3/3]

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

Clones this Body (templated on T) to a body templated on Expression.

Implemented in RigidBody< T >, RigidBody< double >, and RigidBody< AutoDiffXd >.

◆ EvalPoseInWorld()

const math::RigidTransform<T>& EvalPoseInWorld ( const systems::Context< T > &  context) const

Returns the pose X_WB of this body B in the world frame W as a function of the state of the model stored in context.

◆ EvalSpatialVelocityInWorld()

const SpatialVelocity<T>& EvalSpatialVelocityInWorld ( const systems::Context< T > &  context) const

Returns the spatial velocity V_WB of this body B in the world frame W as a function of the state of the model stored in context.

◆ floating_positions_start()

int floating_positions_start ( ) const

(Advanced) For floating bodies (see is_floating()) this method returns the index of the first generalized position in the state vector for a MultibodyPlant model.

Positions for this body are then contiguous starting at this index. When a floating body is modeled with a quaternion mobilizer (see has_quaternion_dofs()), the four consecutive entries in the state starting at this index correspond to the quaternion that parametrizes this body's orientation.

Exceptions
std::exceptionif called pre-finalize, see MultibodyPlant::Finalize().

◆ floating_velocities_start()

int floating_velocities_start ( ) const

(Advanced) For floating bodies (see is_floating()) this method returns the index of the first generalized velocity in the state vector for a MultibodyPlant model.

Velocities for this body are then contiguous starting at this index.

Exceptions
std::exceptionif called pre-finalize, see MultibodyPlant::Finalize().

◆ get_default_mass()

double get_default_mass ( ) const

Returns the default mass (not Context dependent) for this body.

In general, the mass for a body can be a parameter of the model that can be retrieved with the method get_mass(). When the mass of a body is a parameter, the value returned by get_default_mass() is used to initialize the mass parameter in the context.

◆ get_mass()

virtual T get_mass ( const systems::Context< T > &  context) const
pure virtual

(Advanced) Returns the mass of this body stored in context.

Implemented in RigidBody< T >, RigidBody< double >, and RigidBody< AutoDiffXd >.

◆ get_num_flexible_positions()

virtual int get_num_flexible_positions ( ) const
pure virtual

Returns the number of generalized positions q describing flexible deformations for this body.

A rigid body will therefore return zero.

Implemented in RigidBody< T >, RigidBody< double >, and RigidBody< AutoDiffXd >.

◆ get_num_flexible_velocities()

virtual int get_num_flexible_velocities ( ) const
pure virtual

Returns the number of generalized velocities v describing flexible deformations for this body.

A rigid body will therefore return zero.

Implemented in RigidBody< T >, RigidBody< double >, and RigidBody< AutoDiffXd >.

◆ GetForceInWorld()

const SpatialForce<T>& GetForceInWorld ( const systems::Context< T > &  ,
const MultibodyForces< T > &  forces 
) const

Gets the sptatial force on this body B from forces as F_BBo_W: applied at body B's origin Bo and expressed in world world frame W.

◆ has_quaternion_dofs()

bool has_quaternion_dofs ( ) const

(Advanced) If true, this body is a floating body modeled with a quaternion floating mobilizer.

By implication, is_floating() is also true.

See also
floating_positions_start(), floating_velocities_start().
Exceptions
std::exceptionif called pre-finalize, see MultibodyPlant::Finalize().

◆ is_floating()

bool is_floating ( ) const

(Advanced) Returns true if this body is granted 6-dofs by a Mobilizer.

Note
A floating body is not necessarily modeled with a quaternion mobilizer, see has_quaternion_dofs(). Alternative options include a space XYZ parametrization of rotations, see SpaceXYZMobilizer.
Exceptions
std::exceptionif called pre-finalize, see MultibodyPlant::Finalize().

◆ name()

const std::string& name ( ) const

Gets the name associated with this body.

◆ node_index()

internal::BodyNodeIndex node_index ( ) const

(Advanced) Returns the index of the node in the underlying tree structure of the parent MultibodyTree to which this body belongs.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

Friends And Related Function Documentation

◆ internal::BodyAttorney< T >

friend class internal::BodyAttorney< T >
friend

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