ArticulatedInertia_< P > Class Template Reference

An articulated body inertia (ABI) matrix P(q) contains the spatial inertia properties that a body appears to have when it is the free base body of an articulated multibody tree in a given configuration q. More...

#include <MassProperties.h>

List of all members.

Public Member Functions

 ArticulatedInertia_ ()
 ArticulatedInertia_ (const SymMat33P &mass, const Mat33P &massMoment, const SymMat33P &inertia)
 ArticulatedInertia_ (const SpatialInertia_< P > &rbi)
 Construct an articulated body inertia (ABI) from a rigid body spatial inertia (RBI).
ArticulatedInertia_setMass (const SymMat33P &mass)
ArticulatedInertia_setMassMoment (const Mat33P &massMoment)
ArticulatedInertia_setInertia (const SymMat33P &inertia)
const SymMat33PgetMass () const
const Mat33PgetMassMoment () const
const SymMat33PgetInertia () const
ArticulatedInertia_operator+= (const ArticulatedInertia_ &src)
ArticulatedInertia_operator-= (const ArticulatedInertia_ &src)
ArticulatedInertia_ shift (const Vec3P &s) const
 Rigid-shift the origin of this Articulated Body Inertia P by a shift vector s to produce a new ABI P'.
ArticulatedInertia_shiftInPlace (const Vec3P &s)
 Rigid-shift this ABI in place.
const SpatialMatP toSpatialMat () const

Detailed Description

template<class P>
class SimTK::ArticulatedInertia_< P >

An articulated body inertia (ABI) matrix P(q) contains the spatial inertia properties that a body appears to have when it is the free base body of an articulated multibody tree in a given configuration q.

Despite the complex relative motion that occurs within a multibody tree, at any given configuration q there is still a linear relationship between a spatial force F applied to a point of the base body and the resulting acceleration A of that body and that point: F = P(q)*A + c, where c is a velocity- dependent inertial bias force. P is thus analogous to a rigid body spatial inertia (RBI), but for a body which has other bodies connected to it by joints which are free to move.

An ABI P is a symmetric 6x6 spatial matrix, consisting of 2x2 blocks of 3x3 matrices, similar to the RBI. However, unlike the RBI which has only 10 independent elements, all 21 elements of P's lower triangle are significant. For example, the apparent mass of an articulated body depends on which way you push it, and in general there is no well-defined center of mass. This is a much more expensive matrix to manipulate than an RBI. In Simbody's formulation, we only work with ABIs in the Ground frame, so there is never a need to rotate or re-express them. (That is done by rotating RBIs prior to using them to construct the ABIs.) Thus only shifting operations need be performed when transforming ABIs from body to body. Cheap rigid body shifting is done when moving an ABI within a body or across a prescribed mobilizer; otherwise we have to perform an articulated shift operation which is quite expensive.

For a full discussion of the properties of articulated body inertias, see Section 7.1 (pp. 119-123) of Roy Featherstone's excellent 2008 book, Rigid Body Dynamics Algorithms.

In spatial matrix form, an ABI P may be considered to consist of the following 3x3 subblocks:

          P =  [ J  F ]
               [~F  M ]
 

Here M is a (symmetric) mass distribution, F is a full matrix giving the first mass moment distribution, and J is a (symmetric) inertia matrix.


Constructor & Destructor Documentation

ArticulatedInertia_ (  )  [inline]
ArticulatedInertia_ ( const SymMat33P mass,
const Mat33P massMoment,
const SymMat33P inertia 
) [inline]
ArticulatedInertia_ ( const SpatialInertia_< P > &  rbi  )  [inline, explicit]

Construct an articulated body inertia (ABI) from a rigid body spatial inertia (RBI).

Every RBI is also the ABI for that (unarticulated) rigid body.


Member Function Documentation

const SymMat33P& getInertia (  )  const [inline]
const SymMat33P& getMass (  )  const [inline]
const Mat33P& getMassMoment (  )  const [inline]
ArticulatedInertia_& operator+= ( const ArticulatedInertia_< P > &  src  )  [inline]
ArticulatedInertia_& operator-= ( const ArticulatedInertia_< P > &  src  )  [inline]
ArticulatedInertia_& setInertia ( const SymMat33P inertia  )  [inline]
ArticulatedInertia_& setMass ( const SymMat33P mass  )  [inline]
ArticulatedInertia_& setMassMoment ( const Mat33P massMoment  )  [inline]
ArticulatedInertia_ shift ( const Vec3P s  )  const

Rigid-shift the origin of this Articulated Body Inertia P by a shift vector s to produce a new ABI P'.

The calculation is

        P' =  [ J'  F' ]  =  [ 1  sx ] [ J  F ] [ 1  0 ]
              [~F'  M  ]     [ 0  1  ] [~F  M ] [-sx 1 ]
        

where sx is the cross product matrix of s. Cost is 72 flops.

ArticulatedInertia_& shiftInPlace ( const Vec3P s  ) 

Rigid-shift this ABI in place.

72 flops.

See also:
shift() for details
const SpatialMatP toSpatialMat (  )  const [inline]

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

Generated on Thu Aug 12 16:38:17 2010 for SimTKcore by  doxygen 1.6.1