Spatial vector algebra

Index

Types

Coordinate frames

bitstype 64 CartesianFrame3D

A CartesianFrame3D identifies a three-dimensional Cartesian coordinate system.

CartesianFrame3Ds are typically used to annotate the frame in which certain quantities are expressed.

source

Transforms

immutable Transform3D{T<:Number}

A homogeneous transformation matrix representing the transformation from one three-dimensional Cartesian coordinate system to another.

source

Points, free vectors

type Point3D{V<:AbstractArray{T,1}}

A Point3D represents a position in a given coordinate system.

A Point3D is a bound vector. Applying a Transform3D to a Point3D both rotates and translates the Point3D.

source
type FreeVector3D{V<:AbstractArray{T,1}}

A FreeVector3D represents a free vector.

Examples of free vectors include displacements and velocities of points.

Applying a Transform3D to a FreeVector3D only rotates the FreeVector3D.

source

Inertias

immutable SpatialInertia{T<:Number}

A spatial inertia, or inertia matrix, represents the mass distribution of a rigid body.

A spatial inertia expressed in frame $i$ is defined as:

\[I^i = \int_{B}\rho\left(x\right)\left[\begin{array}{cc} \hat{p}^{T}\left(x\right)\hat{p}\left(x\right) & \hat{p}\left(x\right)\\ \hat{p}^{T}\left(x\right) & I \end{array}\right]dx=\left[\begin{array}{cc} J & \hat{c}\\ \hat{c}^{T} & mI \end{array}\right]\]

where $\rho(x)$ is the density of point $x$, and $p(x)$ are the coordinates of point $x$ expressed in frame $i$. $J$ is the mass moment of inertia, $m$ is the total mass, and $c$ is the 'cross part', center of mass position scaled by $m$.

source

Twists, spatial accelerations

immutable Twist{T<:Number}

A twist represents the relative angular and linear motion between two bodies.

The twist of frame $j$ with respect to frame $i$, expressed in frame $k$ is defined as

\[T_{j}^{k,i}=\left(\begin{array}{c} \omega_{j}^{k,i}\\ v_{j}^{k,i} \end{array}\right)\in\mathbb{R}^{6}\]

such that

\[\left[\begin{array}{cc} \hat{\omega}_{j}^{k,i} & v_{j}^{k,i}\\ 0 & 0 \end{array}\right]=H_{i}^{k}\dot{H}_{j}^{i}H_{k}^{j}\]

where $H^{\beta}_{\alpha}$ is the homogeneous transform from frame $\alpha$ to frame $\beta$, and $\hat{x}$ is the $3 \times 3$ skew symmetric matrix that satisfies $\hat{x} y = x \times y$ for all $y \in \mathbb{R}^3$.

Here, $\omega_{j}^{k,i}$ is the angular part and $v_{j}^{k,i}$ is the linear part. Note that the linear part is not in general the same as the linear velocity of the origin of frame $j$.

source
immutable SpatialAcceleration{T<:Number}

A spatial acceleration is the time derivative of a twist.

See Twist.

source

Momenta, wrenches

immutable Momentum{T<:Number}

A Momentum is the product of a SpatialInertia and a Twist, i.e.

\[h^i = \left(\begin{array}{c} k^{i}\\ l^{i} \end{array}\right) = I^i T^{i, j}_k\]

where $I^i$ is the spatial inertia of a given body expressed in frame $i$, and $T^{i, j}_k$ is the twist of frame $k$ (attached to the body) with respect to inertial frame $j$, expressed in frame $i$. $k^i$ is the angular momentum and $l^i$ is the linear momentum.

source
immutable Wrench{T<:Number}

A wrench represents a system of forces.

The wrench $w^i$ expressed in frame $i$ is defined as

\[w^{i} = \left(\begin{array}{c} \tau^{i}\\ f^{i} \end{array}\right) = \sum_{j}\left(\begin{array}{c} r_{j}^{i}\times f_{j}^{i}\\ f_{j}^{i} \end{array}\right)\]

where the $f_{j}^{i}$ are forces expressed in frame $i$, exerted at positions $r_{j}^{i}$. $\tau^i$ is the total torque and $f^i$ is the total force.

source

Geometric Jacobians

immutable GeometricJacobian{A<:AbstractArray{T,2}}

A geometric Jacobian (also known as basic, or spatial Jacobian) maps a vector of joint velocities to a twist.

source

Momentum matrices

immutable MomentumMatrix{A<:AbstractArray{T,2}}

A momentum matrix maps a joint velocity vector to momentum.

This is a slight generalization of the centroidal momentum matrix (Orin, Goswami, "Centroidal momentum matrix of a humanoid robot: Structure and properties.") in that the matrix (and hence the corresponding total momentum) need not be expressed in a centroidal frame.

source

The @framecheck macro

@framecheck(f1, f2)

Check that f1 and f2 are identical (when bounds checks are enabled).

Throws an ArgumentError if f1 is not identical to f2 when bounds checks are enabled. @framecheck is a no-op when bounds checks are disabled.

source

Functions

center_of_mass(inertia)

Return the center of mass of the SpatialInertia as a Point3D.

source
kinetic_energy(I, twist)

Compute the kinetic energy of a body with spatial inertia $I$, which has twist $T$ with respect to an inertial frame.

source
newton_euler(I, Ṫ, T)

Apply the Newton-Euler equations to find the external wrench required to make a body with spatial inertia $I$, which has twist $T$ with respect to an inertial frame, achieve spatial acceleration $\dot{T}$.

This wrench is also equal to the rate of change of momentum of the body.

source
num_cols(jac)

Return the number of columns of the GeometricJacobian.

source
transform(jac, transform)

Transform the GeometricJacobian to a different frame.

source
transform(accel, oldToNew, twistOfCurrentWrtNew, twistOfBodyWrtBase)

Transform the SpatialAcceleration to a different frame.

The transformation rule is obtained by differentiating the transformation rule for twists.

source
transform(inertia, t)

Transform the SpatialInertia to a different frame.

source
transform(twist, transform)

Transform the Twist to a different frame.

source
Base.LinAlg.dotMethod.
dot(w, t)

Compute the mechanical power associated with a pairing of a wrench and a twist.

source
Base.expMethod.
exp(twist)

Convert exponential coordinates to a homogeneous transform.

source
Base.logMethod.
log(t)

Express a homogeneous transform in exponential coordinates centered around the identity.

source
log_with_time_derivative(t, twist)

Compute exponential coordinates as well as their time derivatives in one shot. This mainly exists because ForwardDiff won't work at the singularity of log. It is also ~50% faster than ForwardDiff in this case.

source