Simbody
3.5
|
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...
Public Member Functions | |
ArticulatedInertia_ () | |
Default contruction produces uninitialized junk at zero cost; be sure to fill this in before referencing it. More... | |
ArticulatedInertia_ (const SymMat33P &mass, const Mat33P &massMoment, const SymMat33P &inertia) | |
Construct an ArticulatedInertia from the mass, first moment, and inertia matrices it contains. More... | |
ArticulatedInertia_ (const SpatialInertia_< P > &rbi) | |
Construct an articulated body inertia (ABI) from a rigid body spatial inertia (RBI). More... | |
ArticulatedInertia_ & | setMass (const SymMat33P &mass) |
Set the mass distribution matrix M in this ArticulatedInertia (symmetric). More... | |
ArticulatedInertia_ & | setMassMoment (const Mat33P &massMoment) |
Set the mass first moment distribution matrix F in this ArticulatedInertia (full). More... | |
ArticulatedInertia_ & | setInertia (const SymMat33P &inertia) |
Set the mass second moment (inertia) matrix J in this ArticulatedInertia (symmetric). More... | |
const SymMat33P & | getMass () const |
Get the mass distribution matrix M from this ArticulatedInertia (symmetric). More... | |
const Mat33P & | getMassMoment () const |
Get the mass first moment distribution matrix F from this ArticulatedInertia (full). More... | |
const SymMat33P & | getInertia () const |
Get the mass second moment (inertia) matrix J from this ArticulatedInertia (symmetric). More... | |
ArticulatedInertia_ & | operator+= (const ArticulatedInertia_ &src) |
Add in a compatible ArticulatedInertia to this one. More... | |
ArticulatedInertia_ & | operator-= (const ArticulatedInertia_ &src) |
Subtract a compatible ArticulatedInertia from this one. More... | |
SpatialVecP | operator* (const SpatialVecP &v) const |
Multiply an ArticulatedIneria by a SpatialVec (66 flops). More... | |
template<int N> | |
Mat< 2, N, Vec3P > | operator* (const Mat< 2, N, Vec3P > &m) const |
Multiply an ArticulatedInertia by a row of SpatialVecs (66*N flops). More... | |
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'. More... | |
ArticulatedInertia_ & | shiftInPlace (const Vec3P &s) |
Rigid-shift this ABI in place. More... | |
const SpatialMatP | toSpatialMat () const |
Convert the compactly-stored ArticulatedInertia (21 elements) into a full SpatialMat with 36 elements. More... | |
Related Functions | |
(Note that these are not member functions.) | |
template<class P > | |
ArticulatedInertia_< P > | operator+ (const ArticulatedInertia_< P > &l, const ArticulatedInertia_< P > &r) |
Add two compatible articulated inertias. More... | |
template<class P > | |
ArticulatedInertia_< P > | operator- (const ArticulatedInertia_< P > &l, const ArticulatedInertia_< P > &r) |
Subtract one compatible articulated inertia from another. More... | |
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.
Typedefs exist for the most common invocations of ArticulatedInertia_<P>:
|
inline |
Default contruction produces uninitialized junk at zero cost; be sure to fill this in before referencing it.
|
inline |
Construct an ArticulatedInertia from the mass, first moment, and inertia matrices it contains.
|
inlineexplicit |
Construct an articulated body inertia (ABI) from a rigid body spatial inertia (RBI).
Every RBI is also the ABI for that (unarticulated) rigid body. 12 flops.
|
inline |
Set the mass distribution matrix M in this ArticulatedInertia (symmetric).
|
inline |
Set the mass first moment distribution matrix F in this ArticulatedInertia (full).
|
inline |
Set the mass second moment (inertia) matrix J in this ArticulatedInertia (symmetric).
|
inline |
Get the mass distribution matrix M from this ArticulatedInertia (symmetric).
|
inline |
Get the mass first moment distribution matrix F from this ArticulatedInertia (full).
|
inline |
Get the mass second moment (inertia) matrix J from this ArticulatedInertia (symmetric).
|
inline |
Add in a compatible ArticulatedInertia to this one.
Both inertias must be expressed in the same frame and measured about the same point. 21 flops.
|
inline |
Subtract a compatible ArticulatedInertia from this one.
Both inertias must be expressed in the same frame and measured about the same point. 21 flops.
|
inline |
Multiply an ArticulatedIneria by a SpatialVec (66 flops).
|
inline |
Multiply an ArticulatedInertia by a row of SpatialVecs (66*N flops).
ArticulatedInertia_ SimTK::ArticulatedInertia_< P >::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_& SimTK::ArticulatedInertia_< P >::shiftInPlace | ( | const Vec3P & | s | ) |
|
inline |
Convert the compactly-stored ArticulatedInertia (21 elements) into a full SpatialMat with 36 elements.
|
related |
Add two compatible articulated inertias.
Cost is 21 flops.
|
related |
Subtract one compatible articulated inertia from another.
Cost is 21 flops.