Public Member Functions | Static Public Member Functions | Public Attributes | Private Attributes
tf2::Matrix3x3 Class Reference

The Matrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with Quaternion, Transform and Vector3. Make sure to only include a pure orthogonal matrix without scaling. More...

#include <Matrix3x3.h>

List of all members.

Public Member Functions

 __attribute__ ((deprecated)) void getEulerZYX(tf2Scalar &yaw
 Get the matrix represented as euler angles around ZYX.
Matrix3x3 absolute () const
 Return the matrix with all values non negative.
Matrix3x3 adjoint () const
 Return the adjoint of the matrix.
tf2Scalar cofac (int r1, int c1, int r2, int c2) const
 Calculate the matrix cofactor.
void deSerialize (const struct Matrix3x3Data &dataIn)
void deSerializeDouble (const struct Matrix3x3DoubleData &dataIn)
void deSerializeFloat (const struct Matrix3x3FloatData &dataIn)
tf2Scalar determinant () const
 Return the determinant of the matrix.
void diagonalize (Matrix3x3 &rot, tf2Scalar threshold, int maxSteps)
 diagonalizes this matrix by the Jacobi method.
TF2SIMD_FORCE_INLINE Vector3 getColumn (int i) const
 Get a column of the matrix as a vector.
void getEulerYPR (tf2Scalar &yaw, tf2Scalar &pitch, tf2Scalar &roll, unsigned int solution_number=1) const
 Get the matrix represented as euler angles around YXZ, roundtrip with setEulerYPR.
void getOpenGLSubMatrix (tf2Scalar *m) const
 Fill the values of the matrix into a 9 element array.
void getRotation (Quaternion &q) const
 Get the matrix represented as a quaternion.
TF2SIMD_FORCE_INLINE const
Vector3 & 
getRow (int i) const
 Get a row of the matrix as a vector.
void getRPY (tf2Scalar &roll, tf2Scalar &pitch, tf2Scalar &yaw, unsigned int solution_number=1) const
 Get the matrix represented as roll pitch and yaw about fixed axes XYZ.
Matrix3x3 inverse () const
 Return the inverse of the matrix.
 Matrix3x3 ()
 No initializaion constructor.
 Matrix3x3 (const Quaternion &q)
 Constructor from Quaternion.
 Matrix3x3 (const tf2Scalar &xx, const tf2Scalar &xy, const tf2Scalar &xz, const tf2Scalar &yx, const tf2Scalar &yy, const tf2Scalar &yz, const tf2Scalar &zx, const tf2Scalar &zy, const tf2Scalar &zz)
 Constructor with row major formatting.
TF2SIMD_FORCE_INLINE Matrix3x3 (const Matrix3x3 &other)
 Copy constructor.
Matrix3x3operator*= (const Matrix3x3 &m)
 Multiply by the target matrix on the right.
TF2SIMD_FORCE_INLINE Matrix3x3operator= (const Matrix3x3 &other)
 Assignment Operator.
TF2SIMD_FORCE_INLINE Vector3 & operator[] (int i)
 Get a mutable reference to a row of the matrix as a vector.
TF2SIMD_FORCE_INLINE const
Vector3 & 
operator[] (int i) const
 Get a const reference to a row of the matrix as a vector.
Matrix3x3 scaled (const Vector3 &s) const
 Create a scaled copy of the matrix.
void serialize (struct Matrix3x3Data &dataOut) const
void serializeFloat (struct Matrix3x3FloatData &dataOut) const
void setEulerYPR (tf2Scalar eulerZ, tf2Scalar eulerY, tf2Scalar eulerX)
 Set the matrix from euler angles YPR around ZYX axes.
void setEulerZYX (const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll) __attribute__((deprecated))
 Set the matrix from euler angles using YPR around ZYX respectively.
void setFromOpenGLSubMatrix (const tf2Scalar *m)
 Set from a carray of tf2Scalars.
void setIdentity ()
 Set the matrix to the identity.
void setRotation (const Quaternion &q)
 Set the matrix from a quaternion.
void setRPY (tf2Scalar roll, tf2Scalar pitch, tf2Scalar yaw)
 Set the matrix using RPY about XYZ fixed axes.
void setValue (const tf2Scalar &xx, const tf2Scalar &xy, const tf2Scalar &xz, const tf2Scalar &yx, const tf2Scalar &yy, const tf2Scalar &yz, const tf2Scalar &zx, const tf2Scalar &zy, const tf2Scalar &zz)
 Set the values of the matrix explicitly (row major)
TF2SIMD_FORCE_INLINE tf2Scalar tdotx (const Vector3 &v) const
TF2SIMD_FORCE_INLINE tf2Scalar tdoty (const Vector3 &v) const
TF2SIMD_FORCE_INLINE tf2Scalar tdotz (const Vector3 &v) const
Matrix3x3 timesTranspose (const Matrix3x3 &m) const
Matrix3x3 transpose () const
 Return the transpose of the matrix.
Matrix3x3 transposeTimes (const Matrix3x3 &m) const

Static Public Member Functions

static const Matrix3x3getIdentity ()

Public Attributes

tf2Scalarpitch
tf2Scalar tf2Scalarroll
tf2Scalar tf2Scalar unsigned int solution_number

Private Attributes

Vector3 m_el [3]
 Data storage for the matrix, each vector is a row of the matrix.

Detailed Description

The Matrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with Quaternion, Transform and Vector3. Make sure to only include a pure orthogonal matrix without scaling.

Definition at line 31 of file Matrix3x3.h.


Constructor & Destructor Documentation

No initializaion constructor.

Definition at line 38 of file Matrix3x3.h.

tf2::Matrix3x3::Matrix3x3 ( const Quaternion q) [inline, explicit]

Constructor from Quaternion.

Definition at line 43 of file Matrix3x3.h.

tf2::Matrix3x3::Matrix3x3 ( const tf2Scalar xx,
const tf2Scalar xy,
const tf2Scalar xz,
const tf2Scalar yx,
const tf2Scalar yy,
const tf2Scalar yz,
const tf2Scalar zx,
const tf2Scalar zy,
const tf2Scalar zz 
) [inline]

Constructor with row major formatting.

Definition at line 52 of file Matrix3x3.h.

Copy constructor.

Definition at line 61 of file Matrix3x3.h.


Member Function Documentation

tf2::Matrix3x3::__attribute__ ( (deprecated)  )

Get the matrix represented as euler angles around ZYX.

Parameters:
yawYaw around Z axis
pitchPitch around Y axis
rollaround X axis
solution_numberWhich solution of two possible solutions ( 1 or 2) are possible values

Return the matrix with all values non negative.

Definition at line 539 of file Matrix3x3.h.

Return the adjoint of the matrix.

Definition at line 556 of file Matrix3x3.h.

tf2Scalar tf2::Matrix3x3::cofac ( int  r1,
int  c1,
int  r2,
int  c2 
) const [inline]

Calculate the matrix cofactor.

Parameters:
r1The first row to use for calculating the cofactor
c1The first column to use for calculating the cofactor
r1The second row to use for calculating the cofactor
c1The second column to use for calculating the cofactor See http://en.wikipedia.org/wiki/Cofactor_(linear_algebra) for more details

Definition at line 504 of file Matrix3x3.h.

Definition at line 674 of file Matrix3x3.h.

Definition at line 686 of file Matrix3x3.h.

Definition at line 680 of file Matrix3x3.h.

Return the determinant of the matrix.

Definition at line 532 of file Matrix3x3.h.

void tf2::Matrix3x3::diagonalize ( Matrix3x3 rot,
tf2Scalar  threshold,
int  maxSteps 
) [inline]

diagonalizes this matrix by the Jacobi method.

Parameters:
rotstores the rotation from the coordinate system in which the matrix is diagonal to the original coordinate system, i.e., old_this = rot * new_this * rot^T.
thresholdSee iteration
iterationThe iteration stops when all off-diagonal elements are less than the threshold multiplied by the sum of the absolute values of the diagonal, or when maxSteps have been executed.

Note that this matrix is assumed to be symmetric.

Definition at line 416 of file Matrix3x3.h.

TF2SIMD_FORCE_INLINE Vector3 tf2::Matrix3x3::getColumn ( int  i) const [inline]

Get a column of the matrix as a vector.

Parameters:
iColumn number 0 indexed

Definition at line 81 of file Matrix3x3.h.

void tf2::Matrix3x3::getEulerYPR ( tf2Scalar yaw,
tf2Scalar pitch,
tf2Scalar roll,
unsigned int  solution_number = 1 
) const [inline]

Get the matrix represented as euler angles around YXZ, roundtrip with setEulerYPR.

Parameters:
yawYaw around Z axis
pitchPitch around Y axis
rollaround X axis

Definition at line 292 of file Matrix3x3.h.

static const Matrix3x3& tf2::Matrix3x3::getIdentity ( ) [inline, static]

Definition at line 215 of file Matrix3x3.h.

void tf2::Matrix3x3::getOpenGLSubMatrix ( tf2Scalar m) const [inline]

Fill the values of the matrix into a 9 element array.

Parameters:
mThe array to be filled

Definition at line 225 of file Matrix3x3.h.

void tf2::Matrix3x3::getRotation ( Quaternion q) const [inline]

Get the matrix represented as a quaternion.

Parameters:
qThe quaternion which will be set

Definition at line 243 of file Matrix3x3.h.

TF2SIMD_FORCE_INLINE const Vector3& tf2::Matrix3x3::getRow ( int  i) const [inline]

Get a row of the matrix as a vector.

Parameters:
iRow number 0 indexed

Definition at line 89 of file Matrix3x3.h.

void tf2::Matrix3x3::getRPY ( tf2Scalar roll,
tf2Scalar pitch,
tf2Scalar yaw,
unsigned int  solution_number = 1 
) const [inline]

Get the matrix represented as roll pitch and yaw about fixed axes XYZ.

Parameters:
rollaround X axis
pitchPitch around Y axis
yawYaw around Z axis
solution_numberWhich solution of two possible solutions ( 1 or 2) are possible values

Definition at line 364 of file Matrix3x3.h.

Return the inverse of the matrix.

Definition at line 564 of file Matrix3x3.h.

TF2SIMD_FORCE_INLINE Matrix3x3 & tf2::Matrix3x3::operator*= ( const Matrix3x3 m)

Multiply by the target matrix on the right.

Parameters:
mRotation matrix to be applied Equivilant to this = this * m

Definition at line 523 of file Matrix3x3.h.

TF2SIMD_FORCE_INLINE Matrix3x3& tf2::Matrix3x3::operator= ( const Matrix3x3 other) [inline]

Assignment Operator.

Definition at line 70 of file Matrix3x3.h.

TF2SIMD_FORCE_INLINE Vector3& tf2::Matrix3x3::operator[] ( int  i) [inline]

Get a mutable reference to a row of the matrix as a vector.

Parameters:
iRow number 0 indexed

Definition at line 97 of file Matrix3x3.h.

TF2SIMD_FORCE_INLINE const Vector3& tf2::Matrix3x3::operator[] ( int  i) const [inline]

Get a const reference to a row of the matrix as a vector.

Parameters:
iRow number 0 indexed

Definition at line 105 of file Matrix3x3.h.

Matrix3x3 tf2::Matrix3x3::scaled ( const Vector3 &  s) const [inline]

Create a scaled copy of the matrix.

Parameters:
sScaling vector The elements of the vector will scale each column

Definition at line 372 of file Matrix3x3.h.

Definition at line 661 of file Matrix3x3.h.

Definition at line 667 of file Matrix3x3.h.

void tf2::Matrix3x3::setEulerYPR ( tf2Scalar  eulerZ,
tf2Scalar  eulerY,
tf2Scalar  eulerX 
) [inline]

Set the matrix from euler angles YPR around ZYX axes.

Parameters:
eulerZYaw aboud Z axis
eulerYPitch around Y axis
eulerXRoll about X axis

These angles are used to produce a rotation matrix. The euler angles are applied in ZYX order. I.e a vector is first rotated about X then Y and then Z

Definition at line 180 of file Matrix3x3.h.

void tf2::Matrix3x3::setEulerZYX ( const tf2Scalar yaw,
const tf2Scalar pitch,
const tf2Scalar roll 
) [inline]

Set the matrix from euler angles using YPR around ZYX respectively.

Parameters:
yawYaw about Z axis
pitchPitch about Y axis
rollRoll about X axis

Definition at line 166 of file Matrix3x3.h.

void tf2::Matrix3x3::setFromOpenGLSubMatrix ( const tf2Scalar m) [inline]

Set from a carray of tf2Scalars.

Parameters:
mA pointer to the beginning of an array of 9 tf2Scalars

Definition at line 118 of file Matrix3x3.h.

void tf2::Matrix3x3::setIdentity ( ) [inline]

Set the matrix to the identity.

Definition at line 208 of file Matrix3x3.h.

void tf2::Matrix3x3::setRotation ( const Quaternion q) [inline]

Set the matrix from a quaternion.

Parameters:
qThe Quaternion to match

Definition at line 146 of file Matrix3x3.h.

void tf2::Matrix3x3::setRPY ( tf2Scalar  roll,
tf2Scalar  pitch,
tf2Scalar  yaw 
) [inline]

Set the matrix using RPY about XYZ fixed axes.

Parameters:
rollRoll about X axis
pitchPitch around Y axis
yawYaw aboud Z axis

Definition at line 203 of file Matrix3x3.h.

void tf2::Matrix3x3::setValue ( const tf2Scalar xx,
const tf2Scalar xy,
const tf2Scalar xz,
const tf2Scalar yx,
const tf2Scalar yy,
const tf2Scalar yz,
const tf2Scalar zx,
const tf2Scalar zy,
const tf2Scalar zz 
) [inline]

Set the values of the matrix explicitly (row major)

Parameters:
xxTop left
xyTop Middle
xzTop Right
yxMiddle Left
yyMiddle Middle
yzMiddle Right
zxBottom Left
zyBottom Middle
zzBottom Right

Definition at line 135 of file Matrix3x3.h.

TF2SIMD_FORCE_INLINE tf2Scalar tf2::Matrix3x3::tdotx ( const Vector3 &  v) const [inline]

Definition at line 393 of file Matrix3x3.h.

TF2SIMD_FORCE_INLINE tf2Scalar tf2::Matrix3x3::tdoty ( const Vector3 &  v) const [inline]

Definition at line 397 of file Matrix3x3.h.

TF2SIMD_FORCE_INLINE tf2Scalar tf2::Matrix3x3::tdotz ( const Vector3 &  v) const [inline]

Definition at line 401 of file Matrix3x3.h.

Definition at line 591 of file Matrix3x3.h.

Return the transpose of the matrix.

Definition at line 548 of file Matrix3x3.h.

Definition at line 576 of file Matrix3x3.h.


Member Data Documentation

Vector3 tf2::Matrix3x3::m_el[3] [private]

Data storage for the matrix, each vector is a row of the matrix.

Definition at line 34 of file Matrix3x3.h.

Definition at line 282 of file Matrix3x3.h.

Definition at line 282 of file Matrix3x3.h.

Initial value:
 1) const
        {
                getEulerYPR(yaw, pitch, roll, solution_number);
        }

Definition at line 282 of file Matrix3x3.h.


The documentation for this class was generated from the following file:


tf2
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Oct 2 2017 02:24:35