Spatial vectors are 6-element quantities that are pairs of ordinary 3-vectors.
That is, Drake spatial vectors are logically elements of R³×R³, not R⁶; that is, these are not Plücker vectors! However, we can still operate on them as 6-element column vectors so that we don't have to distinguish rotational from translational operations. Elements 0-2 are always the rotational quantity, elements 3-5 are translational. Here are the spatial vectors we use in Drake:
Spatial: Velocity Acceleration Force --- --- --- Eigen access 0 | | | | | | rotation 1 | ω | | α | | τ | .head<3>() 2 | | | | | | --- --- --- 3 | | | | | | translation 4 | v | | a | | f | .tail<3>() 5 | | | | | | --- --- --- Symbol: V A F
When we need to refer to the underlying 3-vectors in a spatial vector, we use the following symbols, with English alphabet substitutions for their Greek equivalents:
Code | Rotational quantity | Code | Translational quantity | |
---|---|---|---|---|
w | ω - angular velocity | v | linear velocity | |
alpha | α - angular acceleration | a | linear acceleration | |
t | τ - torque | f | force |
While the rotational component of a spatial vector applies to a rigid body or frame as a whole, the translational component refers to a particular point rigidly fixed to that same body or frame. When assigned numerical values for computation, both subvectors must be expressed in the same frame, which may be that body's frame or any other specified frame. Thus, unambiguous notation for spatial vectors must specify both a point and an expressed-in frame. Motion quantities must also state the reference frame with respect to which the motion is measured.
Example spatial quantity | At | Exp | Typeset | Code | Full |
---|---|---|---|---|---|
Body B's spatial velocity in A | Bo | A | \(^AV^B \) | V_AB | V_ABo_A |
Same, but expressed in world | Bo | W | \([^AV^B]_W \) | V_AB_W | V_ABo_W |
B's spatial acceleration in W | Bcm | W | \(^WA^{B_{cm}} \) | A_WBcm | A_WBcm_W |
Spatial force acting on body B | Bcm | W | \([F^{B_{cm}}]_W\) | F_Bcm_W | F_BBcm_W |
Spatial force acting on body B | Bq | W | \([F^{B_q}]_W \) | F_Bq_W | F_BBq_W |
In the above table "At" is the point at which the translational activity occurs; "Exp" is the expressed-in frame in which both vectors are expressed. In cases in which the typeset has a top-left superscript frame (such as spatial velocity or spatial acceleration), the default expressed-in frame is that top-left frame. If the typeset has a top-right superscript frame, the default point is the origin of that top-right frame. The "Code" column shows the notation to use in code (abbreviated via default conventions); "Full" shows the code notation without the abbreviated defaults (i.e., fully explicit).
For spatial forces we need to identify the body (or frame) on which the force is acting, as well as a point rigidly fixed to that body (or frame). When the body is obvious from the point name (such as Bo or Bcm above), the body does not need to be specified again. However, when the body is not clear it should be listed before the point as in the last line of the table above. There it can be read as "point Bq of body B" or "point Bq is the point of body B which is coincident in space with point Q", where point Q may be fixed to a different body. Use fully- expanded symbols, and helpful comments, if there is any chance of confusion.
Next topic: Spatial Mass Matrix (Spatial Inertia)