M-File Help: Twist | View code for Twist |
SE(2) and SE(3) Twist class
A Twist class holds the parameters of a twist, a representation of a rigid body displacement in SE(2) or SE(3).
S | twist vector (1x3 or 1x6) |
se | twist as (augmented) skew-symmetric matrix (3x3 or 4x4) |
T | convert to homogeneous transformation (3x3 or 4x4) |
R | convert rotational part to matrix (2x2 or 3x3) |
exp | synonym for T |
ad | logarithm of adjoint |
pitch | pitch of the screw, SE(3) only |
pole | a point on the line of the screw |
theta | rotation about the screw |
line | Plucker line object representing line of the screw |
display | print the Twist parameters in human readable form |
char | convert to string |
SE | convert to SE2 or SE3 object |
double | convert to real vector |
* | compose two Twists |
* | multiply Twist by a scalar |
v | moment part of twist (2x1 or 3x1) |
w | direction part of twist (1x1 or 3x1) |
Create Twist object
tw = Twist(T) is a Twist object representing the SE(2) or SE(3) homogeneous transformation matrix T (3x3 or 4x4).
tw = Twist(v) is a twist object where the vector is specified directly.
3D CASE::
tw = Twist('R', A, Q) is a Twist object representing rotation about the axis of direction A (3x1) and passing through the point Q (3x1).
tw = Twist('R', A, Q, P) as above but with a pitch of P (distance/angle).
tw = Twist('T', A) is a Twist object representing translation in the direction of A (3x1).
2D CASE::
tw = Twist('R', Q) is a Twist object representing rotation about the point Q (2x1).
tw = Twist('T', A) is a Twist object representing translation in the direction of A (2x1).
The argument 'P' for prismatic is synonymous with 'T'.
Logarithm of adjoint
TW.ad is the logarithm of the adjoint matrix of the corresponding homogeneous transformation.
Convert to string
s = TW.char() is a string showing Twist parameters in a compact single line format. If TW is a vector of Twist objects return a string with one line per Twist.
Display parameters
L.display() displays the twist parameters in compact single line format. If L is a vector of Twist objects displays one line per element.
Return the twist vector
double(tw) is the twist vector in se(2) or se(3) as a vector (1x3 or 1x6).
Convert twist to homogeneous transformation
TW.exp is the homogeneous transformation equivalent to the twist (3x3 or 4x4).
TW.exp(theta) as above but with a rotation of theta about the twist.
Line of twist axis in Plucker form
TW.line is a Plucker object representing the line of the twist axis.
Multiply twist by twist or scalar
TW1 * TW2 is a new Twist representing the composition of twists TW1 and TW2.
TW * S with its twist coordinates scaled by scalar S.
Pitch of the twist
TW.pitch is the pitch of the Twist as a scalar in units of distance per radian.
Point on the twist axis
TW.pole is a point on the twist axis (2x1 or 3x1).
Return the twist vector
TW.S is the twist vector in se(2) or se(3) as a vector (3x1 or 6x1).
Convert twist to SE2 or SE3 object
TW.SE is an SE2 or SE3 object representing the homogeneous transformation equivalent to the twist.
Return the twist matrix
TW.se is the twist matrix in se(2) or se(3) which is an augmented skew-symmetric matrix (3x3 or 4x4).
Convert twist to homogeneous transformation
TW.T is the homogeneous transformation equivalent to the twist (3x3 or 4x4).
TW.T(theta) as above but with a rotation of theta about the twist.
Twist rotation
TW.theta is the rotation (1x1) about the twist axis in radians.
© 1990-2014 Peter Corke.