Drake
Drake C++ Documentation

Quantities of interest in multibody dynamics have distinct types.

For example, a rotation matrix is denoted with R and a position vector with p. New quantities can be created by differentiation of an existing quantity (see Time Derivatives of Multibody Quantities).

Most quantities have a reference and target, either of which may be a frame, basis, or point, that specify how the quantity is defined. In computation, vectors are expressed in a specified basis (or frame) that associates a direction with each vector element. For example, the velocity of a point P moving in a reference frame F is a vector quantity with target point P and reference frame F. In typeset this symbol is written as \(^Fv^P\). Here v is the quantity type, the left superscript F is the reference, and the right superscript P is the target. In computation, this vector is expressed in a particular basis. By default, the assumed expressed-in frame is the same as the reference frame, so in this case, the assumed expressed-in frame is frame F's basis. Alternately, to use a different expressed-in frame, say W, typeset with the bracket notation: \([^Fv^P]_W\).

Kane/monogram notation was developed decades ago for kinematics and dynamics. It explicitly communicates the quantity being measured and how it is expressed. The typeset symbol \(^Fv^P\) is translated to monogram notation as v_FP. The quantity type always comes first, then an underscore, then left and right superscripts. By default, the symbol v_FP implies the vector is expressed in frame F. Alternately, to express in frame W, use the typeset \([^Fv^P]_W\) and monogram notation v_FP_W (add a final underscore and expressed-in frame W). We adhere to this pattern for all quantities and it is quite useful once you get familiar with it. As a second example, consider the position vector of point Bcm (body B's center of mass) from point Bo (the origin of frame B), expressed in B. In explicit typeset, this is \([^{B_o}p^{B_{cm}}]_B \) whereas in implicit typeset this is abbreviated \(^Bp^{B_{cm}}\) (where the left-superscript B denotes Bo and the expressed-in frame is implied to be B). The corresponding monogram equivalents are p_BoBcm_B and p_BBcm, respectively.

Here are some more useful multibody quantities.

Quantity Symbol Typeset Monogram Meaningᵃ
Generic vector v v \([v]_E\) v_E Vector v expressed in frame E.
Rotation matrix R \(^BR^C\) R_BC Frame C's orientation in frame B
Position vector p \(^Bp^C\) p_BC Position vector from Bo (frame B's origin) to Co (frame C's origin), expressed in frame B (implied).
Position vector p \([^Pp^Q]_E\) p_PQ_E Position vector from point P to point Q, expressed in frame E.
Transform/pose X \(^BX^C\) X_BC Frame C's rigid transform (pose) in frame B
General Transform T \(^BT^C\) T_BC The relationship between two spaces – it may be affine, projective, isometric, etc. Every X_AB can be written as T_AB, but not every T_AB can be written as X_AB.
Angular velocity w \(^B\omega^C\) w_BC Frame C's angular velocity in frame Bᵃ
Velocity v \(^Bv^Q\) v_BQ Point Q's translational velocity in frame B
Relative velocity v \(^Bv^{Q/P}\) v_B_PQ Point Q's translational velocity relative to point P in frame B
Spatial velocity V \(^BV^{C}\) V_BC Frame C's spatial velocity in frame B (for point Co)ᵇ
Relative spatial velocity V \(^BV^{C/D}\) V_B_DC Frame C's spatial velocity relative to frame D in frame B
Angular acceleration alpha \(^B\alpha^C\) alpha_BC Frame C's angular acceleration in frame B
Acceleration a \(^Ba^Q\) a_BQ Point Q's translational acceleration in frame B
Relative acceleration a \(^Ba^{Q/P}\) a_B_PQ Point Q's translational acceleration relative to point P in frame B
Spatial acceleration A \(^BA^{C}\) A_BC Frame C's spatial acceleration in frame B (for point Co)ᵇ
Relative spatial acceleration A \(^BA^{C/D}\) A_B_DC Frame C's spatial acceleration relative to frame D in frame B
Torque t \(\tau^{B}\) t_B Torque on a body (or frame) B
Force f \(f^{P}\) f_P Force on a point P
Spatial force F \(F^{B}\) F_B Spatial force (torque/force) on a body (or frame) Bᶜ
Inertia matrix I \(I^{B/Bo}\) I_BBo Body B's inertia matrix about Bo
Spatial inertia M \(M^{B/Bo}\) M_BBo Body B's spatial inertia about Boᵃ
Spatial momentum L \(^BL^{S/P}\) L_BSP System S's spatial momentum about point P in frame B
Spatial momentum L \(^BL^{S/Scm}\) L_BScm System S's spatial momentum about point Scm in frame B
Kinetic energy K \(^BK^S\) K_BS System S's kinetic energy in frame B
Jacobian wrt qᵈ Jq \([J_{q}^{{}^Pp^Q}]_E\) Jq_p_PQ_E Point Q's position Jacobian from point P in frame E wrt q (in means both measured-in and expressed-in)
Jacobian wrt q̇ Jqdot \(J_{q̇}^{{}^Bv^Q}\) Jqdot_v_BQ Point Q's translational velocity Jacobian in frame B wrt q̇
Jacobian wrt v Jv \(J_{v}^{{}^Bv^Q}\) Jv_v_BQ Point Q's translational velocity Jacobian in frame B wrt v
Jacobian wrt v Jv \(J_{v}^{{}^B\omega^C}\) Jv_w_BC Frame C's angular velocity Jacobian in frame B wrt v
Ez measure of vector v v \([v]_{Ez}\) v_Ez Ez scalar component of vector v, i.e., v • Ez, where Ez is frame E's z-direction unit vector.

ᵃ In code, a vector has an expressed-in-frame which appears after the quantity.
Example: w_BC_E is C's angular velocity in B, expressed in frame E, typeset as \([^B\omega^C]_E \). If not explicitly present, the expressed-in-frame defaults to the measured-in-frame. Hence, w_BC is C's angular velocity in (measured-in) frame B, expressed in frame B (implied).
Similarly, an inertia matrix or spatial inertia has an expressed-in-frame.
Example: I_BBo_E is body B's inertia matrix about Bo, expressed in frame E, typeset as \([I^{B/Bo}]_E\).
By convention, I_BP is body B's inertia matrix about point P, expressed in B (implied).
For more information, see Spatial Mass Matrix (Spatial Inertia)

ᵇ In code, spatial velocity (or spatial acceleration) has an expressed-in-frame which appears after the quantity.
Example: V_BC_E is frame C's spatial velocity in frame B, expressed in frame E and contains both w_BC_E (described aboveᵃ) and v_BC_E (point Co's translational velocity in frame B, expressed in frame E). Reminder, a rigid body D's translational and spatial velocity are for point Do (the origin of D's body frame), not for Dcm (D's center of mass). See Frames and Bodies for more information.

ᶜ It is often useful to replace a set of forces on a body or frame B by an equivalent set with a force \(f^{Bo}\) (equal to the set's resultant) placed at Bo, together with a torque \(\tau\) equal to the moment of the set about Bo. A spatial force Fᴮᵒ containing \(\tau\) and \(f^{Bo}\) represents this replacement. Note: the spatial force Fᴮ is shorthand for Fᴮᵒ (i.e., the about-point is B's origin Bo). The monogram notation F_Bcm is useful when the about-point is Bcm (body B's center of mass).

ᵈ The Jacobian contains partial derivatives wrt (with respect to) scalars e.g., wrt q (generalized positions), or q̇, or v (generalized velocities). The example below shows the simplicity of Jacobian monogram: first is the Jacobian symbol (Jv), next is the kinematic quantity (v_BQ), last is an expressed-in frame (E).
Example: Jv_v_BQ_E is Jv (Jacobian wrt v), for v_BQ (velocity in frame B of point Q), expressed in frame E.
Advanced: Due to rules of vector differentiation, explicit Jacobian monogram notation for Jq (Jacobian wrt generalized positions q) requires an extra frame (e.g., JBq is partial differentiation in frame B wrt q). Frequently, the partial-differentiation-in-frame B is identical to the expressed-in-frame E and a shorthand notation can be used.
Example: Jq_p_PQ_E is Jq (Jacobian in frame E wrt q), for p_PQ (position vector from point P to point Q), expressed in frame E.
Special relationship between position and velocity Jacobians: When a point Q's position vector originates at a point Bo fixed in frame B and when there are no motion constraints (no relationships between q̇₁ ... q̇ₙ), \(\;[J_{q}^{{}^{Bo}p^Q}]_B = [J_{q̇}^{{}^Bv^Q}]_B\;\) i.e., (Jq_p_BoQ_B = Jqdot_v_BQ_B).

Monogram notation addresses frequently used kinematics. In a context-sensible way (and in collaboration with reviewers), extend notation to related concepts. Some examples are shown below.

Extended notation Description (herein E is the vectors' expressed-in-frame)
p_PQset_E p_PQlist_E Set of position vectors from a point P to each of the points in the set Q = {Q₀, Q₁, Q₂, ...}
v_BQset_E v_BQlist_E Set of translational velocities in frame B for the set of points Q = {Q₀, Q₁, Q₂, ...}
w_BCset_E w_BClist_E Set of angular velocities in frame B for the frames in the set C = {C₀, C₁, C₂, ...}
vset_E vlist_E Set of generic vectors v = {v₀, v₁, v₂} expressed in frame E
mesh_B A mesh whose underlying vertices' positions are from Bo (frame B's origin), expressed in frame B
point_cloud_B A point cloud whose underlying points' positions are from Bo (frame B's origin), expressed in frame B

Next topic: Units of Multibody Quantities