Matlab API

Warning

MATLAB® scripts are a work in progress and will generally lag behind the available Python scripts.

Main module

The functions in the main module can be called with MR.function-name.

R_p_to_SE3(R, p)

Constructs a homogeneous transformation matrix from a rotation matrix and displacement vector.

Parameters
  • R – 3 by 3 rotation matrix \(\RotationMatrix\in\SOthree\)

  • p – 3 by 1 displacement vector

Returns

4 by 4 homogeneous transformation matrix \(\HomogeneousTransformationMatrix \in \SEthree\)

SE3_to_vec(T)

‘Differentiation’ of a transformation matrix by using the matrix log of its rotation matrix to determine the screw velocity vector (twist) that reaches this transformation in unit time.

Parameters

T – Homogeneous transformation matrix

Returns

Velocity twist vector \(\Twist\) with length \(\theta\)

See also

vec_to_SE3()

SO3_to_vec(R)

‘Differentiation’ of a rotation matrix by using the matrix log to determine the angular velocity that reaches that orientation in unit time.

Parameters

R – 3 by 3 rotation matrix \(\RotationMatrix \in \SOthree\).

Returns

Angular velocity vector \(\omega\) with length \(\theta\).

See also

so3_to_vec() vec_to_SO3()

big_adjoint(T)

Constructs the ‘big adjoint’ form of the transformation matrix T.

\[\begin{split}\HomogeneousTransformationMatrix = \begin{bmatrix} \RotationMatrix & p \\ 0 & 1 \end{bmatrix} \quad\Rightarrow\quad \Adjoint{\HomogeneousTransformationMatrix} = \begin{bmatrix} \RotationMatrix & 0 \\ \TildeSkew{p}\RotationMatrix & \RotationMatrix \end{bmatrix}\end{split}\]
Parameters

T – 4 by 4 homogeneous transformation matrix \(\HomogeneousTransformationMatrix \in \SEthree\)

Returns

6 by 6 ‘big adjoint’ form of the transformation matrix T

Example

>> T = [eye(3), [1; 2; 3]; 0, 0, 0, 1];
>> MR.big_adjoint(T)

ans =

     1     0     0     0     0     0
     0     1     0     0     0     0
     0     0     1     0     0     0
     0    -3     2     1     0     0
     3     0    -1     0     1     0
    -2     1     0     0     0     1
inv_SE3(T)

Inverts the transformation matrix T.

\[\begin{split}\HomogeneousTransformationMatrix = \begin{bmatrix} \RotationMatrix & p \\ 0 & 1 \end{bmatrix}\in\SEthree \quad\Rightarrow\quad \HomogeneousTransformationMatrix^{-1} = \begin{bmatrix} \RotationMatrix\Transposed & -\RotationMatrix\Transposed p \\ 0 & 1 \end{bmatrix}\in\SEthree\end{split}\]
Parameters

T – 4 by 4 homogeneous transformation matrix \(\HomogeneousTransformationMatrix \in \SEthree\)

Returns

4 by 4 inverse of the homogeneous transformation matrix \(\HomogeneousTransformationMatrix^{-1} \in \SEthree\)

little_adjoint(V)

Constructs the ‘little adjoint’ form of the velocity twist V.

\[\begin{split}\Twist = \begin{bmatrix} \omega \\ v \end{bmatrix} \quad\Rightarrow\quad \LittleAdjoint{\Twist} = \begin{bmatrix} \TildeSkew{\omega} & 0 \\ \TildeSkew{v} & \TildeSkew{\omega} \end{bmatrix}\end{split}\]
Parameters

V – 6 by 1 velocity twist

Returns

6 by 6 ‘little adjoint’ form of the twist V

Example

>> V = [1; 2; 3; 4; 5; 6];
>> MR.little_adjoint(V)

ans =

     0    -3     2     0     0     0
     3     0    -1     0     0     0
    -2     1     0     0     0     0
     0    -6     5     0    -3     2
     6     0    -4     3     0    -1
    -5     4     0    -2     1     0
little_so3_to_vec(v_tilde)

Reconstruct a 3 vector from its skew-symmetric matrix form. No check is performed to see if v_tilde is really skew-symmetric.

Parameters

v_tilde – 3 by 3 skew-symmetric matrix form of v, \(\TildeSkew{v}\).

Returns

3 vector.

See also

vec_to_so3()

vec_to_SE3(S, theta)

‘Integration’ of a velocity twist to determine the configuration (expressed as transformation matrix) that this velocity twist reaches in unit time.

Parameters
  • S – 6 vector velocity twist

  • theta – Distance travelled along the velocity twist screw axis

Returns

4 by 4 homogeneous transformation matrix \(\HomogeneousTransformationMatrix \in \SEthree\)

See also

SE3_to_vec()

vec_to_SO3(omega, theta)

‘Integration’ of an angular velocity to determine the orientation (expressed as rotation matrix) that this angular velocity reaches in unit time.

Uses Rodrigues’ formula to solve the matrix exponential of the vector’s skew-symmetric matrix form.

\[\RotationMatrix = \exp(\TildeSkew{\UnitLength{\omega}}\theta) = I + \TildeSkew{\UnitLength{\omega}}\sin\theta + \TildeSkew{\UnitLength{\omega}}^2(1-\cos\theta) \in \SOthree\]
Parameters
  • omega – 3 vector angular velocity. Can be unit length, in that case theta should also be provided.

  • theta – If omitted, the Euclidean norm of omega is assumed to be theta.

Returns

3 by 3 rotation matrix \(\RotationMatrix \in \SOthree\).

See also

vec_to_so3() SO3_to_vec()

vec_to_little_so3(v)

Build a skew-symmetric matrix from a 3 vector.

Parameters

v – 3 vector.

Returns

3 by 3 skew-symmetric matrix form of v, \(\TildeSkew{v}\).

See also

so3_to_vec()

gen submodule

The +MR.+gen submodule contains functions to easiliy construct homogeneous transformation matrices with base transformations. The functions in this submodule can be called with MR.gen.function-name.

TRx(theta)

Creates a transformation matrix with a single rotation around the \(x\)-axis.

Parameters

theta – Angle to rotate with around \(x\), in radians.

Returns

Homogeneous transformation matrix with \(x\)-rotation and zero translation.

Example

>> MR.gen.TRx(pi/6)

ans =

    1.0000         0         0         0
         0    0.8660   -0.5000         0
         0    0.5000    0.8660         0
         0         0         0    1.0000

See also

TRy() TRz()

TRy(theta)

Creates a transformation matrix with a single rotation around the \(y\)-axis.

Parameters

theta – Angle to rotate with around \(y\), in radians.

Returns

Homogeneous transformation matrix with \(y\)-rotation and zero translation.

Example

>> MR.gen.TRy(pi/6)

ans =

    0.8660         0    0.5000         0
         0    1.0000         0         0
   -0.5000         0    0.8660         0
         0         0         0    1.0000

See also

TRx() TRz()

TRz(theta)

Creates a transformation matrix with a single rotation around the \(z\)-axis.

Parameters

theta – Angle to rotate with around \(z\), in radians.

Returns

Homogeneous transformation matrix with \(z\)-rotation and zero translation.

Example

>> MR.gen.TRx(pi/6)

ans =

    0.8660   -0.5000         0         0
    0.5000    0.8660         0         0
         0         0    1.0000         0
         0         0         0    1.0000

See also

TRx() TRy()

Tt(varargin)

Creates a transformation matrix with only a translational part.

Parameters
  • t – Translation three vector. Should be a column vector. Optional, if omitted use one of the following to create t.

  • x\(x\)-coordinate of the translation. Optional and only used if t is not provided.

  • y\(y\)-coordinate of the translation. Optional and only used if t is not provided.

  • z\(z\)-coordinate of the translation. Optional and only used if t is not provided.

Returns

Homogeneous transformation matrix without rotation, only translation.

Examples

>> MR.gen.Tt([1;2;3])

ans =

     1     0     0     1
     0     1     0     2
     0     0     1     3
     0     0     0     1
>> MR.gen.Tt('y', 2, 'z', 6)

ans =

     1     0     0     0
     0     1     0     2
     0     0     1     6
     0     0     0     1