M-File Help: SO2 View code for SO2

SO2

Representation of 2D rotation

This subclasss of RTBPose is an object that represents an SO(2) rotation

Constructor methods

SO2 general constructor
SO2.exp exponentiate an so(2) matrix
SO2.rand random orientation
new new SO2 object

Information and test methods

dim* returns 2
isSE* returns false
issym* true if rotation matrix has symbolic elements
isa check if matrix is SO2

Display and print methods

plot* graphically display coordinate frame for pose
animate* graphically animate coordinate frame for pose
print* print the pose in single line format
display* print the pose in human readable matrix form
char* convert to human readable matrix as a string

Operation methods

det determinant of matrix component
eig eigenvalues of matrix component
log logarithm of rotation matrix
inv inverse
simplify* apply symbolic simplication to all elements
interp interpolate between rotations

Conversion methods

check convert object or matrix to SO2 object
theta return rotation angle
double convert to rotation matrix
R convert to rotation matrix
SE2 convert to SE2 object with zero translation
T convert to homogeneous transformation matrix with zero translation

Compatibility methods

isrot2* returns true
ishomog2* returns false
trprint2* print single line representation
trplot2* plot coordinate frame

tranimate2* animate coordinate frame

* means inherited from RTBPose

Operators

+ elementwise addition, result is a matrix
- elementwise subtraction, result is a matrix
* multiplication within group, also group x vector
/ multiply by inverse
== test equality
~= test inequality

See also

SE2, SO3, SE3, RTBPose


SO2.SO2

Construct an SO(2) object

p = SO2() is an SO2 object representing null rotation.

p = SO2(theta) is an SO2 object representing rotation of theta radians. If theta is a vector (N) then p is a vector of objects, corresponding to the elements of theta.

p = SO2(theta, 'deg') as above but with theta degrees.

p = SO2(R) is an SO2 object formed from the rotation matrix R (2x2)

p = SO2(T) is an SO2 object formed from the rotational part of the homogeneous transformation matrix T (3x3)

P = SO2(Q) is an SO2 object that is a copy of the SO2 object Q. %

See also

rot2, SE2, SO3


SO2.angle

Rotation angle

theta = P.angle() is the rotation angle, in radians, associated with the SO2 object P.


SO2.char

Convert to string

s = P.char() is a string containing rotation matrix elements.

See also

RTB.display


SO2.check

Convert to SO2

q = SO2.check(x) is an SO2 object where x is SO2, 2x2, SE2 or 3x3 homogeneous transformation matrix.


SO2.det

Determinant of SO2 object

det(p) is the determinant of the SO2 object p and should always be +1.


SO2.eig

Eigenvalues and eigenvectors

E = eig(p) is a column vector containing the eigenvalues of the the rotation matrix of the SO2 object p.

[v,d] = eig(p) produces a diagonal matrix d of eigenvalues and a full matrix v whose columns are the corresponding eigenvectors so that A*v = v*d.

See also

eig


SO2.exp

Construct SO2 object from Lie algebra

p = SO2.exp(so2) creates an SO2 object by exponentiating the se(2) argument (2x2).


SO2.interp

Interpolate between SO2 objects

P1.interp(p2, s) is an SO2 object representing interpolation between rotations represented by SO2 objects P1 and p2. s varies from 0 (P1) to 1 (p2). If s is a vector (1xN) then the result will be a vector of SO2 objects.

Notes

See also

SO2.angle


SO2.inv

Inverse of SO2 object

q = inv(p) is the inverse of the SO2 object p. p*q will be the identity matrix.

Notes


SO2.isa

Test if matrix is SO(2)

SO2.ISA(T) is true (1) if the argument T is of dimension 2x2 or 2x2xN, else false (0).

SO2.ISA(T, true) as above, but also checks the validity of the rotation matrix, ie. its determinant is +1.

Notes

See also

SO3.ISA, SE2.ISA, SE2.ISA, ishomog2


SO2.log

Lie algebra

so2 = P.log() is the Lie algebra skew-symmetric matrix (2x2) corresponding to the SO2 object P.


SO2.new

Construct a new object of the same type

p2 = P.new(x) creates a new object of the same type as P, by invoking the SO2 constructor on the matrix x (2x2).

p2 = P.new() as above but defines a null motion.

Notes

See also

SE3.new, SO3.new, SE2.new


SO2.R

Get rotation matrix

R = P.R() is the rotation matrix (2x2) associated with the SO2 object P. If P is a vector (1xN) then R (2x2xN) is a stack of rotation matrices, with the third dimension corresponding to the index of P.

See also

SO2.T


SO2.rand

Construct a random SO(2) object

SO2.rand() is an SO2 object with a uniform random orientation. Random numbers are in the interval 0 to 1.

See also

rand


SO2.SE2

Convert to SE2 object

q = P.SE2() is an SE2 object formed from the rotational component of the SO2 object P and with a zero translational component.

See also

SE2


SO2.T

Get homogeneous transformation matrix

T = P.T() is the homogeneous transformation matrix (3x3) associated with the SO2 object P, and has zero translational component. If P is a vector (1xN) then T (3x3xN) is a stack of rotation matrices, with the third dimension corresponding to the index of P.

See also

SO2.T


SO2.theta

Rotation angle

theta = P.theta() is the rotation angle, in radians, associated with the SO2 object P.

Notes


 

© 1990-2014 Peter Corke.