M-File Help: Quaternion | View code for Quaternion |
Quaternion class
A quaternion is a compact method of representing a 3D rotation that has computational advantages including speed and numerical robustness. A quaternion has 2 parts, a scalar s, and a vector v and is typically written: q = s <vx, vy, vz>.
A unit-quaternion is one for which sˆ2+vxˆ2+vyˆ2+vzˆ2 = 1. It can be considered as a rotation by an angle theta about a unit-vector V in space where
q = cos (theta/2) < v sin(theta/2)>
q = quaternion(x) is a unit-quaternion equivalent to x which can be any of:
inv | inverse of quaterion |
norm | norm of quaternion |
unit | unitized quaternion |
plot | same options as trplot() |
interp | interpolation (slerp) between q and q2, 0<=s<=1 |
scale | interpolation (slerp) between identity and q, 0<=s<=1 |
dot | derivative of quaternion with angular velocity w |
R | equivalent 3x3 rotation matrix |
T | equivalent 4x4 homogeneous transform matrix |
q1==q2 | test for quaternion equality |
q1~=q2 | test for quaternion inequality |
q+q2 | elementwise sum of quaternions |
q-q2 | elementwise difference of quaternions |
q*q2 | quaternion product |
q*v | rotate vector by quaternion, v is 3x1 |
s*q | elementwise multiplication of quaternion by scalar |
q/q2 | q*q2.inv |
q^n | q to power n (integer only) |
s | real part |
v | vector part |
Constructor for quaternion objects
Construct a quaternion from various other orientation representations.
q = Quaternion() is the identitity quaternion 1<0,0,0> representing a null rotation.
q = Quaternion(q1) is a copy of the quaternion q1
q = Quaternion([S V1 V2 V3]) is a quaternion formed by specifying directly its 4 elements
q = Quaternion(s) is a quaternion formed from the scalar s and zero vector part: s<0,0,0>
q = Quaternion(v) is a pure quaternion with the specified vector part: 0<v>
q = Quaternion(th, v) is a unit-quaternion corresponding to rotation of th about the vector v.
q = Quaternion(R) is a unit-quaternion corresponding to the orthonormal rotation matrix R. If R (3x3xN) is a sequence then q (Nx1) is a vector of Quaternions corresponding to the elements of R.
q = Quaternion(T) is a unit-quaternion equivalent to the rotational part of the homogeneous transform T. If T (4x4xN) is a sequence then q (Nx1) is a vector of Quaternions corresponding to the elements of T.
Convert to string
s = Q.char() is a compact string representation of the quaternion's value as a 4-tuple. If Q is a vector then s has one line per element.
Display the value of a quaternion object
Q.display() displays a compact string representation of the quaternion's value as a 4-tuple. If Q is a vector then S has one line per element.
Convert a quaternion to a 4-element vector
v = Q.double() is a 4-vector comprising the quaternion elements [s vx vy vz].
Test quaternion equality
Q1==Q2 is true if the quaternions Q1 and Q2 are equal.
Interpolate quaternions
qi = Q1.interp(q2, s) is a unit-quaternion that interpolates a rotation between Q1 for s=0 and q2 for s=1.
If s is a vector qi is a vector of quaternions, each element corresponding to sequential elements of s.
Invert a unit-quaternion
qi = Q.inv() is a quaternion object representing the inverse of Q.
Subtract quaternions
Q1-Q2 is the element-wise difference of quaternion elements.
Quaternion.plus, Quaternion.mtimes
Raise quaternion to integer power
QˆN is the quaternion Q raised to the integer power N.
Quaternion.mrdivide, Quaternion.mpower, Quaternion.plus, Quaternion.minus
Quaternion quotient.
Q1/Q2 | is a quaternion formed by Hamilton product of Q1 and inv(Q2). |
Q/S | is the element-wise division of quaternion elements by the scalar S. |
Quaternion.mtimes, Quaternion.mpower, Quaternion.plus, Quaternion.minus
Multiply a quaternion object
Q1*Q2 | is a quaternion formed by the Hamilton product of two quaternions. |
Q*V | is a vector formed by rotating the vector V by the quaternion Q. |
Q*S | is the element-wise multiplication of quaternion elements by the scalar S. |
Quaternion.mrdivide, Quaternion.mpower, Quaternion.plus, Quaternion.minus
Test quaternion inequality
Q1~=Q2 is true if the quaternions Q1 and Q2 are not equal.
Quaternion magnitude
qn = q.norm(q) is the scalar norm or magnitude of the quaternion q.
Plot a quaternion object
Q.plot(options) plots the quaternion as a rotated coordinate frame.
Options are passed to trplot and include:
'color', C | The color to draw the axes, MATLAB colorspec C |
'frame', F | The frame is named {F} and the subscript on the axis labels is F. |
'view', V | Set plot view parameters V=[az el] angles, or 'auto' for view toward origin of coordinate frame |
Add quaternions
Q1+Q2 is the element-wise sum of quaternion elements.
Quaternion.minus, Quaternion.mtimes
Convert toorthonormal rotation matrix
R = Q.R() is the equivalent 3x3 orthonormal rotation matrix.
Notes:
Interpolate rotations expressed by quaternion objects
qi = Q.scale(s) is a unit-quaternion that interpolates between identity for s=0 to Q for s=1. This is a spherical linear interpolation (slerp) that can be interpretted as interpolation along a great circle arc on a sphere.
If s is a vector qi is a cell array of quaternions, each element corresponding to sequential elements of s.
Convert to homogeneous transformation matrix
T = Q.T() is the equivalent 4x4 homogeneous transformation matrix.
Notes:
Unitize a quaternion
qu = Q.unit() is a unit-quaternion representing the same orientation as Q.
© 1990-2012 Peter Corke.