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

Detailed Description

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

The term rigid body implies that the deformations of the body under consideration are so small that they have no significant effect on the overall motions of the body and therefore deformations can be neglected.

If deformations are neglected, the distance between any two points on the rigid body remains constant at all times. This invariance of the distance between two arbitrary points is often taken as the definition of a rigid body in classical treatments of multibody mechanics [Goldstein 2001]. It can be demonstrated that the unconstrained three-dimensional motions of a rigid body can be described by six coordinates and thus it is often said that a free body in space has six degrees of freedom. These degrees of freedom obey the Newton-Euler equations of motion. However, within a MultibodyTree, a RigidBody is not free in space; instead, it is assigned a limited number of degrees of freedom (0-6) with respect to its parent body in the multibody tree by its Mobilizer (also called a "tree joint" or "inboard joint"). Additional constraints on permissible motion can be added using Constraint objects to remove more degrees of freedom.

  • [Goldstein 2001] H Goldstein, CP Poole, JL Safko, Classical Mechanics (3rd Edition), Addison-Wesley, 2001.
Template Parameters
TThe scalar type, which must be one of the default scalars.

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

Public Member Functions

 RigidBody (const std::string &body_name, const SpatialInertia< double > &M_BBo_B=SpatialInertia< double >::Zero())
 Constructs a RigidBody named body_name with the given default SpatialInertia. More...
 
 RigidBody (const std::string &body_name, ModelInstanceIndex model_instance, const SpatialInertia< double > &M_BBo_B=SpatialInertia< double >::Zero())
 Constructs a RigidBody named body_name with the given default SpatialInertia. More...
 
BodyIndex index () const
 Returns this element's unique index. More...
 
const std::string & name () const
 Gets the name associated with this rigid body. More...
 
ScopedName scoped_name () const
 Returns scoped name of this frame. More...
 
const RigidBodyFrame< T > & body_frame () const
 Returns a const reference to the associated BodyFrame. More...
 
void Lock (systems::Context< T > *context) const
 For a floating RigidBody, lock its inboard joint. More...
 
void Unlock (systems::Context< T > *context) const
 For a floating RigidBody, unlock its inboard joint. More...
 
bool is_locked (const systems::Context< T > &context) const
 Determines whether this RigidBody is currently locked to its inboard (parent) RigidBody. More...
 
internal::MobodIndex mobod_index () const
 (Advanced) Returns the index of the mobilized body ("mobod") in the computational directed forest structure of the owning MultibodyTree to which this RigidBody belongs. More...
 
bool is_floating () const
 (Advanced) Returns true if this body is granted 6-dofs by a Mobilizer and the parent body of this body's associated 6-dof joint is world. More...
 
bool has_quaternion_dofs () const
 (Advanced) If true, this body's generalized position coordinates q include a quaternion, which occupies the first four elements of q. More...
 
int floating_positions_start () const
 (Advanced) For floating bodies (see is_floating()) this method returns the index of this RigidBody's first generalized position in the vector q of generalized position coordinates for a MultibodyPlant model. More...
 
int floating_velocities_start_in_v () const
 (Advanced) For floating bodies (see is_floating()) this method returns the index of this RigidBody's first generalized velocity in the vector v of generalized velocities for a MultibodyPlant model. More...
 
std::string floating_position_suffix (int position_index_in_body) const
 Returns a string suffix (e.g. More...
 
std::string floating_velocity_suffix (int velocity_index_in_body) const
 Returns a string suffix (e.g. More...
 
double default_mass () const
 Returns this RigidBody's default mass, which is initially supplied at construction when specifying this body's SpatialInertia. More...
 
const Vector3< double > & default_com () const
 Returns the default value of this RigidBody's center of mass as measured and expressed in its body frame. More...
 
const UnitInertia< double > & default_unit_inertia () const
 Returns the default value of this body B's unit inertia about Bo (body B's origin), expressed in B (this body's body frame). More...
 
RotationalInertia< doubledefault_rotational_inertia () const
 Gets the default value of this body B's rotational inertia about Bo (B's origin), expressed in B (this body's body frame). More...
 
const SpatialInertia< double > & default_spatial_inertia () const
 Gets the default value of this body B's SpatialInertia about Bo (B's origin) and expressed in B (this body's frame). More...
 
const T & get_mass (const systems::Context< T > &context) const
 Gets this body's mass from the given context. More...
 
const math::RigidTransform< T > & EvalPoseInWorld (const systems::Context< T > &context) const
 Returns the pose X_WB of this RigidBody 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
 Evaluates V_WB, this body B's SpatialVelocity in the world frame W. More...
 
const SpatialAcceleration< T > & EvalSpatialAccelerationInWorld (const systems::Context< T > &context) const
 Evaluates A_WB, this body B's SpatialAcceleration in the world frame W. More...
 
const SpatialForce< T > & GetForceInWorld (const systems::Context< T > &, const MultibodyForces< T > &forces) const
 Gets the SpatialForce on this RigidBody B from forces as F_BBo_W: applied at body B's origin Bo and expressed in world frame W. More...
 
void AddInForceInWorld (const systems::Context< T > &, const SpatialForce< T > &F_Bo_W, MultibodyForces< T > *forces) const
 Adds the SpatialForce on this RigidBody 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 SpatialForce on this RigidBody B, applied at point P and expressed in a frame E into forces. More...
 
const Vector3< T > CalcCenterOfMassInBodyFrame (const systems::Context< T > &context) const
 Gets this body's center of mass position from the given context. More...
 
Vector3< T > CalcCenterOfMassTranslationalVelocityInWorld (const systems::Context< T > &context) const
 Calculates Bcm's translational velocity in the world frame W. More...
 
SpatialInertia< T > CalcSpatialInertiaInBodyFrame (const systems::Context< T > &context) const
 Gets this body's spatial inertia about its origin from the given context. More...
 
void SetMass (systems::Context< T > *context, const T &mass) const
 For this RigidBody B, sets its mass stored in context to mass. More...
 
void SetCenterOfMassInBodyFrame (systems::Context< T > *context, const Vector3< T > &com) const
 (Advanced) Sets this body's center of mass position while preserving its inertia about its body origin. More...
 
void SetCenterOfMassInBodyFrameAndPreserveCentralInertia (systems::Context< T > *context, const Vector3< T > &center_of_mass_position) const
 Sets this body's center of mass position while preserving its inertia about its center of mass. More...
 
void SetSpatialInertiaInBodyFrame (systems::Context< T > *context, const SpatialInertia< T > &M_Bo_B) const
 For this RigidBody B, sets its SpatialInertia that is stored in context to M_Bo_B. More...
 
template<typename ToScalar >
std::unique_ptr< RigidBody< ToScalar > > CloneToScalar (const internal::MultibodyTree< ToScalar > &tree_clone) const
 (Advanced) This method is mostly intended to be called by MultibodyTree::CloneToScalar(). More...
 
Does not allow copy, move, or assignment
 RigidBody (const RigidBody &)=delete
 
RigidBodyoperator= (const RigidBody &)=delete
 
 RigidBody (RigidBody &&)=delete
 
RigidBodyoperator= (RigidBody &&)=delete
 
Methods to access position kinematics quantities.

The input PositionKinematicsCache to these methods must be in sync with context.

These method's APIs will be deprecated when caching arrives.

const math::RigidTransform< T > & get_pose_in_world (const internal::PositionKinematicsCache< T > &pc) const
 (Advanced) Extract this body's pose in world (from the position kinematics). More...
 
const math::RotationMatrix< T > get_rotation_matrix_in_world (const internal::PositionKinematicsCache< T > &pc) const
 (Advanced) Extract the RotationMatrix relating the world frame to this body's frame. More...
 
const Vector3< T > get_origin_position_in_world (const internal::PositionKinematicsCache< T > &pc) const
 (Advanced) Extract the position vector from world origin to this body's origin, expressed in world. More...
 
Methods to access velocity kinematics quantities.

The input VelocityKinematicsCache to these methods must be in sync with context.

These method's APIs will be deprecated when caching arrives.

const SpatialVelocity< T > & get_spatial_velocity_in_world (const internal::VelocityKinematicsCache< T > &vc) const
 (Advanced) Returns V_WB, this RigidBody B's SpatialVelocity in the world frame W. More...
 
const Vector3< T > & get_angular_velocity_in_world (const internal::VelocityKinematicsCache< T > &vc) const
 (Advanced) Extract this body's angular velocity in world, expressed in world. More...
 
const Vector3< T > & get_origin_velocity_in_world (const internal::VelocityKinematicsCache< T > &vc) const
 (Advanced) Extract the velocity of this body's origin in world, expressed in world. More...
 
Methods to access acceleration kinematics quantities.

The input AccelerationKinematicsCache to these methods must be in sync with context.

These method APIs will be deprecated when caching arrives.

const SpatialAcceleration< T > & get_spatial_acceleration_in_world (const internal::AccelerationKinematicsCache< T > &ac) const
 (Advanced) Returns A_WB, this RigidBody B's SpatialAcceleration in the world frame W. More...
 
const Vector3< T > & get_angular_acceleration_in_world (const internal::AccelerationKinematicsCache< T > &ac) const
 (Advanced) Extract this body's angular acceleration in world, expressed in world. More...
 
const Vector3< T > & get_origin_acceleration_in_world (const internal::AccelerationKinematicsCache< T > &ac) const
 (Advanced) Extract acceleration of this body's origin in world, expressed in world. 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
 

Friends

class internal::RigidBodyAttorney< T >
 

Additional Inherited Members

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

◆ RigidBody() [1/4]

RigidBody ( const RigidBody< T > &  )
delete

◆ RigidBody() [2/4]

RigidBody ( RigidBody< T > &&  )
delete

◆ RigidBody() [3/4]

RigidBody ( const std::string &  body_name,
const SpatialInertia< double > &  M_BBo_B = SpatialInertiadouble >::Zero() 
)
explicit

Constructs a RigidBody named body_name with the given default SpatialInertia.

Parameters
[in]body_nameA name associated with this body.
[in]M_BBo_BSpatial inertia of this body B about the frame's origin Bo and expressed in the body frame B. When not provided, defaults to zero.
Note
See Spatial Mass Matrix (Spatial Inertia) for details on the monogram notation used for spatial inertia quantities.

◆ RigidBody() [4/4]

RigidBody ( const std::string &  body_name,
ModelInstanceIndex  model_instance,
const SpatialInertia< double > &  M_BBo_B = SpatialInertiadouble >::Zero() 
)

Constructs a RigidBody named body_name with the given default SpatialInertia.

Parameters
[in]body_nameA name associated with this body.
[in]model_instanceThe model instance associated with this body.
[in]M_BBo_BSpatial inertia of this body B about the frame's origin Bo and expressed in the body frame B. When not provided, defaults to zero.
Note
See Spatial Mass Matrix (Spatial Inertia) for details on the monogram notation used for spatial inertia quantities.

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 SpatialForce on this RigidBody 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 SpatialForce on this RigidBody B, applied at body B's origin Bo and expressed in the world frame W into forces.

◆ body_frame()

const RigidBodyFrame<T>& body_frame ( ) const

Returns a const reference to the associated BodyFrame.

◆ CalcCenterOfMassInBodyFrame()

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

Gets this body's center of mass position from the given context.

Parameters
[in]contextcontains the state of the multibody system.
Returns
p_BoBcm_B position vector from Bo (this rigid body B's origin) to Bcm (B's center of mass), expressed in B.
Precondition
the context makes sense for use by this RigidBody.

◆ CalcCenterOfMassTranslationalVelocityInWorld()

Vector3<T> CalcCenterOfMassTranslationalVelocityInWorld ( const systems::Context< T > &  context) const

Calculates Bcm's translational velocity in the world frame W.

Parameters
[in]contextThe context contains the state of the model.
Return values
v_WBcm_WThe translational velocity of Bcm (this rigid body's center of mass) in the world frame W, expressed in W.

◆ CalcSpatialInertiaInBodyFrame()

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

Gets this body's spatial inertia about its origin from the given context.

Parameters
[in]contextcontains the state of the multibody system.
Returns
M_BBo_B spatial inertia of this rigid body B about Bo (B's origin), expressed in B. M_BBo_B contains properties related to B's mass, the position vector from Bo to Bcm (B's center of mass), and G_BBo_B (B's unit inertia about Bo expressed in B).
Precondition
the context makes sense for use by this RigidBody.

◆ CloneToScalar()

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

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

◆ default_com()

const Vector3<double>& default_com ( ) const

Returns the default value of this RigidBody's center of mass as measured and expressed in its body frame.

This value is initially supplied at construction when specifying this body's SpatialInertia.

Return values
p_BoBcm_BThe position of this rigid body B's center of mass Bcm measured from Bo (B's frame origin) and expressed in B (body B's frame).

◆ default_mass()

double default_mass ( ) const

Returns this RigidBody's default mass, which is initially supplied at construction when specifying this body's SpatialInertia.

Note
In general, a rigid body's mass can be a constant property stored in this rigid body's SpatialInertia or a parameter that is stored in a Context. The default constant mass value is used to initialize the mass parameter in the Context.

◆ default_rotational_inertia()

RotationalInertia<double> default_rotational_inertia ( ) const

Gets the default value of this body B's rotational inertia about Bo (B's origin), expressed in B (this body's body frame).

This value is calculated from the SpatialInertia supplied at construction of this body.

Return values
I_BBo_Bbody B's rotational inertia about Bo, expressed in B.

◆ default_spatial_inertia()

const SpatialInertia<double>& default_spatial_inertia ( ) const

Gets the default value of this body B's SpatialInertia about Bo (B's origin) and expressed in B (this body's frame).

Return values
M_BBo_Bbody B's spatial inertia about Bo, expressed in B.

◆ default_unit_inertia()

const UnitInertia<double>& default_unit_inertia ( ) const

Returns the default value of this body B's unit inertia about Bo (body B's origin), expressed in B (this body's body frame).

This value is initially supplied at construction when specifying this body's SpatialInertia.

Return values
G_BBo_Brigid body B's unit inertia about Bo, expressed in B.

◆ EvalPoseInWorld()

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

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

◆ EvalSpatialAccelerationInWorld()

const SpatialAcceleration<T>& EvalSpatialAccelerationInWorld ( const systems::Context< T > &  context) const

Evaluates A_WB, this body B's SpatialAcceleration in the world frame W.

Parameters
[in]contextContains the state of the model.
Return values
A_WB_Wthis body B's spatial acceleration in the world frame W, expressed in W (for point Bo, the body's origin).
Note
When cached values are out of sync with the state stored in context, this method performs an expensive forward dynamics computation, whereas once evaluated, successive calls to this method are inexpensive.

◆ EvalSpatialVelocityInWorld()

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

Evaluates V_WB, this body B's SpatialVelocity in the world frame W.

Parameters
[in]contextContains the state of the model.
Return values
V_WB_Wthis body B's spatial velocity in the world frame W, expressed in W (for point Bo, the body frame's origin).

◆ floating_position_suffix()

std::string floating_position_suffix ( int  position_index_in_body) const

Returns a string suffix (e.g.

to be appended to the name()) to identify the kth position in the floating base. position_index_in_body must be in [0, 7) if has_quaternion_dofs() is true, otherwise in [0, 6).

Exceptions
std::exceptionif called pre-finalize
Precondition
this is a floating body
See also
is_floating(), has_quaternion_dofs(), MultibodyPlant::Finalize()

◆ floating_positions_start()

int floating_positions_start ( ) const

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

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

Exceptions
std::exceptionif called pre-finalize
Precondition
this is a floating body
See also
is_floating(), has_quaternion_dofs(), MultibodyPlant::Finalize()

◆ floating_velocities_start_in_v()

int floating_velocities_start_in_v ( ) const

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

Velocities v for this RigidBody are then contiguous starting at this index.

Exceptions
std::exceptionif called pre-finalize
Precondition
this is a floating body
See also
is_floating(), MultibodyPlant::Finalize()

◆ floating_velocity_suffix()

std::string floating_velocity_suffix ( int  velocity_index_in_body) const

Returns a string suffix (e.g.

to be appended to the name()) to identify the kth velocity in the floating base. velocity_index_in_body must be in [0,6).

Exceptions
std::exceptionif called pre-finalize
Precondition
this is a floating body
See also
is_floating(), MultibodyPlant::Finalize()

◆ get_angular_acceleration_in_world()

const Vector3<T>& get_angular_acceleration_in_world ( const internal::AccelerationKinematicsCache< T > &  ac) const

(Advanced) Extract this body's angular acceleration in world, expressed in world.

Parameters
[in]acvelocity kinematics cache.
Return values
alpha_WB_WB's angular acceleration in world W, expressed in W.

◆ get_angular_velocity_in_world()

const Vector3<T>& get_angular_velocity_in_world ( const internal::VelocityKinematicsCache< T > &  vc) const

(Advanced) Extract this body's angular velocity in world, expressed in world.

Parameters
[in]vcvelocity kinematics cache.
Return values
w_WB_Wrigid body B's angular velocity in world W, expressed in W.

◆ get_mass()

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

Gets this body's mass from the given context.

Parameters
[in]contextcontains the state of the multibody system.
Precondition
the context makes sense for use by this RigidBody.

◆ get_origin_acceleration_in_world()

const Vector3<T>& get_origin_acceleration_in_world ( const internal::AccelerationKinematicsCache< T > &  ac) const

(Advanced) Extract acceleration of this body's origin in world, expressed in world.

Parameters
[in]vcvelocity kinematics cache.
Return values
a_WBo_Wacceleration of body origin Bo in world W, expressed in W.

◆ get_origin_position_in_world()

const Vector3<T> get_origin_position_in_world ( const internal::PositionKinematicsCache< T > &  pc) const

(Advanced) Extract the position vector from world origin to this body's origin, expressed in world.

Parameters
[in]pcposition kinematics cache.
Return values
p_WoBo_Wposition vector from Wo (world origin) to Bo (this body's origin) expressed in W (world).

◆ get_origin_velocity_in_world()

const Vector3<T>& get_origin_velocity_in_world ( const internal::VelocityKinematicsCache< T > &  vc) const

(Advanced) Extract the velocity of this body's origin in world, expressed in world.

Parameters
[in]vcvelocity kinematics cache.
Return values
v_WBo_Wvelocity of Bo (body origin) in world W, expressed in W.

◆ get_pose_in_world()

const math::RigidTransform<T>& get_pose_in_world ( const internal::PositionKinematicsCache< T > &  pc) const

(Advanced) Extract this body's pose in world (from the position kinematics).

Parameters
[in]pcposition kinematics cache.
Return values
X_WBpose of rigid body B in world frame W.

◆ get_rotation_matrix_in_world()

const math::RotationMatrix<T> get_rotation_matrix_in_world ( const internal::PositionKinematicsCache< T > &  pc) const

(Advanced) Extract the RotationMatrix relating the world frame to this body's frame.

Parameters
[in]pcposition kinematics cache.
Return values
R_WBrotation matrix relating rigid body B in world frame W.

◆ get_spatial_acceleration_in_world()

const SpatialAcceleration<T>& get_spatial_acceleration_in_world ( const internal::AccelerationKinematicsCache< T > &  ac) const

(Advanced) Returns A_WB, this RigidBody B's SpatialAcceleration in the world frame W.

Parameters
[in]acacceleration kinematics cache.
Return values
A_WB_Wthis rigid body B's spatial acceleration in the world frame W, expressed in W (for point Bo, the body frame's origin).

◆ get_spatial_velocity_in_world()

const SpatialVelocity<T>& get_spatial_velocity_in_world ( const internal::VelocityKinematicsCache< T > &  vc) const

(Advanced) Returns V_WB, this RigidBody B's SpatialVelocity in the world frame W.

Parameters
[in]vcvelocity kinematics cache.
Return values
V_WB_Wthis rigid body B's spatial velocity in the world frame W, expressed in W (for point Bo, the body frame's origin).

◆ GetForceInWorld()

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

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

◆ has_quaternion_dofs()

bool has_quaternion_dofs ( ) const

(Advanced) If true, this body's generalized position coordinates q include a quaternion, which occupies the first four elements of q.

Note that this does not imply that the body is floating since it may have fewer than 6 dofs or its inboard body could be something other than World.

Exceptions
std::exceptionif called pre-finalize
See also
is_floating(), MultibodyPlant::Finalize()

◆ index()

BodyIndex index ( ) const

Returns this element's unique index.

◆ is_floating()

bool is_floating ( ) const

(Advanced) Returns true if this body is granted 6-dofs by a Mobilizer and the parent body of this body's associated 6-dof joint is world.

Note
A floating body is not necessarily modeled with a quaternion mobilizer, see has_quaternion_dofs(). Alternative options include a roll-pitch-yaw (rpy) parametrization of rotations, see RpyFloatingMobilizer.
Exceptions
std::exceptionif called pre-finalize,
See also
MultibodyPlant::Finalize()

◆ is_locked()

bool is_locked ( const systems::Context< T > &  context) const

Determines whether this RigidBody is currently locked to its inboard (parent) RigidBody.

This is not limited to floating bodies but generally Joint::is_locked() is preferable otherwise.

Returns
true if the body is locked, false otherwise.

◆ Lock()

void Lock ( systems::Context< T > *  context) const

For a floating RigidBody, lock its inboard joint.

Its generalized velocities will be 0 until it is unlocked.

Exceptions
std::exceptionif this body is not a floating body.

◆ mobod_index()

internal::MobodIndex mobod_index ( ) const

(Advanced) Returns the index of the mobilized body ("mobod") in the computational directed forest structure of the owning MultibodyTree to which this RigidBody belongs.

This serves as the BodyNode index and the index into all associated quantities.

◆ name()

const std::string& name ( ) const

Gets the name associated with this rigid body.

The name will never be empty.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ scoped_name()

ScopedName scoped_name ( ) const

Returns scoped name of this frame.

Neither of the two pieces of the name will be empty (the scope name and the element name).

◆ SetCenterOfMassInBodyFrame()

void SetCenterOfMassInBodyFrame ( systems::Context< T > *  context,
const Vector3< T > &  com 
) const

(Advanced) Sets this body's center of mass position while preserving its inertia about its body origin.

Parameters
[in,out]contextcontains the state of the multibody system. It is modified to store the updated com (center of mass position).
[in]composition vector from Bo (this body B's origin) to Bcm (B's center of mass), expressed in B.
Note
This function changes B's center of mass position without modifying G_BBo_B (B's unit inertia about Bo, expressed in B). Since this use case is very unlikely, consider using SetSpatialInertiaInBodyFrame() or SetCenterOfMassInBodyFrameAndPreserveCentralInertia().
Precondition
the context makes sense for use by this RigidBody.
Exceptions
std::exceptionif context is null.
Warning
Do not use this function unless it is needed (think twice).

◆ SetCenterOfMassInBodyFrameAndPreserveCentralInertia()

void SetCenterOfMassInBodyFrameAndPreserveCentralInertia ( systems::Context< T > *  context,
const Vector3< T > &  center_of_mass_position 
) const

Sets this body's center of mass position while preserving its inertia about its center of mass.

Parameters
[in,out]contextcontains the state of the multibody system. It is modified to store the updated center_of_mass_position and the updated G_BBo_B (this body B's unit inertia about B's origin Bo, expressed in B).
[in]center_of_mass_positionposition vector from Bo to Bcm (B's center of mass), expressed in B.
Note
G_BBo_B is modified to ensure B's inertia about Bcm is unchanged. Although this function can work well when B's mass is concentrated at (or mostly near) a single point, it has questionable utility to generally account for inertia changes due to arbitrary center of mass changes. Consider using SetSpatialInertiaInBodyFrame() instead.
Precondition
the context makes sense for use by this RigidBody.
Exceptions
std::exceptionif context is null.

◆ SetMass()

void SetMass ( systems::Context< T > *  context,
const T &  mass 
) const

For this RigidBody B, sets its mass stored in context to mass.

Parameters
[out]contextcontains the state of the multibody system.
[in]massmass of this rigid body B.
Note
This function changes this body B's mass and appropriately scales I_BBo_B (B's rotational inertia about Bo, expressed in B).
Precondition
the context makes sense for use by this RigidBody.
Exceptions
std::exceptionif context is null.

◆ SetSpatialInertiaInBodyFrame()

void SetSpatialInertiaInBodyFrame ( systems::Context< T > *  context,
const SpatialInertia< T > &  M_Bo_B 
) const

For this RigidBody B, sets its SpatialInertia that is stored in context to M_Bo_B.

Parameters
[out]contextcontains the state of the multibody system.
[in]M_Bo_Bspatial inertia of this rigid body B about Bo (B's origin), expressed in B. M_Bo_B contains properties related to B's mass, the position vector from Bo to Bcm (B's center of mass), and G_Bo_B (B's unit inertia about Bo expressed in B).
Precondition
the context makes sense for use by this RigidBody.
Exceptions
std::exceptionif context is null.

◆ Unlock()

void Unlock ( systems::Context< T > *  context) const

For a floating RigidBody, unlock its inboard joint.

Exceptions
std::exceptionif this body is not a floating body.

Friends And Related Function Documentation

◆ internal::RigidBodyAttorney< T >

friend class internal::RigidBodyAttorney< T >
friend

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