Drake
RigidBody< T > Class Template Reference

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

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

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

Public Member Functions

 RigidBody (const SpatialInertia< double > M_BBo_B)
 Constructs a RigidBody with the given default SpatialInertia. More...
 
int get_num_flexible_positions () const final
 There are no flexible degrees of freedom associated with a rigid body and therefore this method returns zero. More...
 
int get_num_flexible_velocities () const final
 There are no flexible degrees of freedom associated with a rigid body and therefore this method returns zero. More...
 
double get_default_mass () const
 Returns the default value of this body's mass. More...
 
const Vector3< double > & get_default_com () const
 Returns the default value of this rigid body's center of mass as measured and expressed in this body's frame. More...
 
const UnitInertia< double > & get_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 frame). More...
 
RotationalInertia< doubleget_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 frame). More...
 
get_mass (const MultibodyTreeContext< T > &) const final
 Returns the mass of this body stored in context. More...
 
const Vector3< T > CalcCenterOfMassInBodyFrame (const MultibodyTreeContext< T > &) const final
 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...
 
SpatialInertia< T > CalcSpatialInertiaInBodyFrame (const MultibodyTreeContext< T > &) const override
 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...
 
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 Isometry3< T > & get_pose_in_world (const PositionKinematicsCache< T > &pc) const
 Extract this body's pose in world (from the position kinematics). More...
 
const Matrix3< T > get_body_orientation_in_world (const PositionKinematicsCache< T > &pc) const
 Extract the rotation matrix relating the world frame to this body's frame. More...
 
const Vector3< T > get_origin_position_in_world (const PositionKinematicsCache< T > &pc) const
 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 VelocityKinematicsCache< T > &vc) const
 Extract this body spatial velocity in world, expressed in world. More...
 
const Vector3< T > & get_angular_velocity_in_world (const VelocityKinematicsCache< T > &vc) const
 Extract this body angular velocity in world, expressed in world. More...
 
const Vector3< T > & get_origin_velocity_in_world (const VelocityKinematicsCache< T > &vc) const
 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 AccelerationKinematicsCache< T > &ac) const
 Extract this body spatial acceleration in world, expressed in world. More...
 
const Vector3< T > & get_angular_acceleration_in_world (const AccelerationKinematicsCache< T > &ac) const
 Extract this body's angular acceleration in world, expressed in world. More...
 
const Vector3< T > & get_origin_acceleration_in_world (const AccelerationKinematicsCache< T > &ac) const
 Extract acceleration of this body's origin in world, expressed in world. More...
 
- Public Member Functions inherited from Body< T >
 Body ()
 Creates a Body with a BodyFrame associated with it. More...
 
const BodyFrame< T > & get_body_frame () const
 Returns a const reference to the associated BodyFrame. More...
 
BodyNodeIndex get_node_index () const
 Returns the index of the node in the underlying tree structure of the parent MultibodyTree to which this body belongs. More...
 
template<typename ToScalar >
std::unique_ptr< Body< ToScalar > > CloneToScalar (const MultibodyTree< ToScalar > &tree_clone) const
 NVI (Non-Virtual Interface) to DoCloneToScalar() templated on the scalar type of the new clone to be created. More...
 
 Body (const Body &)=delete
 
Bodyoperator= (const Body &)=delete
 
 Body (Body &&)=delete
 
Bodyoperator= (Body &&)=delete
 

Protected Member Functions

std::unique_ptr< Body< double > > DoCloneToScalar (const MultibodyTree< double > &tree_clone) const final
 Clones this Body (templated on T) to a body templated on double. More...
 
std::unique_ptr< Body< AutoDiffXd > > DoCloneToScalar (const MultibodyTree< AutoDiffXd > &tree_clone) const final
 Clones this Body (templated on T) to a body templated on AutoDiffXd. More...
 
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.

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

RigidBody ( const RigidBody< T > &  )
delete
RigidBody ( RigidBody< T > &&  )
delete
RigidBody ( const SpatialInertia< double M_BBo_B)
explicit

Constructs a RigidBody with the given default SpatialInertia.

Parameters
[in]M_BBo_BSpatial inertia of this body B about the frame's origin Bo and expressed in the body frame B.
Note
See Spatial Mass Matrix (Spatial Inertia) for details on the monogram notation used for spatial inertia quantities.

Member Function Documentation

const Vector3<T> CalcCenterOfMassInBodyFrame ( const MultibodyTreeContext< T > &  context) const
inlinefinalvirtual

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.

Implements Body< T >.

SpatialInertia<T> CalcSpatialInertiaInBodyFrame ( const MultibodyTreeContext< T > &  context) const
inlineoverridevirtual

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.

Implements Body< T >.

std::unique_ptr<Body<double> > DoCloneToScalar ( const MultibodyTree< double > &  tree_clone) const
inlinefinalprotectedvirtual

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

Implements Body< T >.

std::unique_ptr<Body<AutoDiffXd> > DoCloneToScalar ( const MultibodyTree< AutoDiffXd > &  tree_clone) const
inlinefinalprotectedvirtual

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

Implements Body< T >.

const Vector3<T>& get_angular_acceleration_in_world ( const AccelerationKinematicsCache< T > &  ac) const
inline

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.
const Vector3<T>& get_angular_velocity_in_world ( const VelocityKinematicsCache< T > &  vc) const
inline

Extract this body 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.
const Matrix3<T> get_body_orientation_in_world ( const PositionKinematicsCache< T > &  pc) const
inline

Extract the rotation matrix 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.
const Vector3<double>& get_default_com ( ) const
inline

Returns the default value of this rigid body's center of mass as measured and expressed in this body's 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).

Here is the caller graph for this function:

double get_default_mass ( ) const
inline

Returns the default value of this body's mass.

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

Returns
This body's default mass.
RotationalInertia<double> get_default_rotational_inertia ( ) const
inline

Gets the default value of this body B's rotational inertia about Bo (B's origin), expressed in B (this body's 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.
const UnitInertia<double>& get_default_unit_inertia ( ) const
inline

Returns the default value of this body B's unit inertia about Bo (body B's origin), expressed in B (this body's 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.
T get_mass ( const MultibodyTreeContext< T > &  context) const
inlinefinalvirtual

Returns the mass of this body stored in context.

Implements Body< T >.

Here is the caller graph for this function:

int get_num_flexible_positions ( ) const
inlinefinalvirtual

There are no flexible degrees of freedom associated with a rigid body and therefore this method returns zero.

By definition, a rigid body has no state associated with flexible deformations.

Implements Body< T >.

int get_num_flexible_velocities ( ) const
inlinefinalvirtual

There are no flexible degrees of freedom associated with a rigid body and therefore this method returns zero.

By definition, a rigid body has no state associated with flexible deformations.

Implements Body< T >.

const Vector3<T>& get_origin_acceleration_in_world ( const AccelerationKinematicsCache< T > &  ac) const
inline

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.
const Vector3<T> get_origin_position_in_world ( const PositionKinematicsCache< T > &  pc) const
inline

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).
const Vector3<T>& get_origin_velocity_in_world ( const VelocityKinematicsCache< T > &  vc) const
inline

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.
const Isometry3<T>& get_pose_in_world ( const PositionKinematicsCache< T > &  pc) const
inline

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.

Here is the caller graph for this function:

const SpatialAcceleration<T>& get_spatial_acceleration_in_world ( const AccelerationKinematicsCache< T > &  ac) const
inline

Extract this body spatial acceleration in world, expressed in world.

Parameters
[in]acacceleration kinematics cache.
Return values
A_WB_Wbody B's spatial acceleration in world W, expressed in W.

Here is the caller graph for this function:

const SpatialVelocity<T>& get_spatial_velocity_in_world ( const VelocityKinematicsCache< T > &  vc) const
inline

Extract this body spatial velocity in world, expressed in world.

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

Here is the caller graph for this function:

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

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