Class Matrix3x3

Class Documentation

class Matrix3x3

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.

Public Functions

inline Matrix3x3()

No initializaion constructor.

inline explicit Matrix3x3(const Quaternion &q)

Constructor from Quaternion.

inline 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.

inline Matrix3x3(const Matrix3x3 &other)

Copy constructor.

inline Matrix3x3 &operator=(const Matrix3x3 &other)

Assignment Operator.

inline Vector3 getColumn(int i) const

Get a column of the matrix as a vector.

Parameters:

i – Column number 0 indexed

inline const Vector3 &getRow(int i) const

Get a row of the matrix as a vector.

Parameters:

i – Row number 0 indexed

inline Vector3 &operator[](int i)

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

Parameters:

i – Row number 0 indexed

inline const Vector3 &operator[](int i) const

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

Parameters:

i – Row number 0 indexed

Matrix3x3 &operator*=(const Matrix3x3 &m)

Multiply by the target matrix on the right.

Parameters:

m – Rotation matrix to be applied Equivilant to this = this * m

inline void setFromOpenGLSubMatrix(const tf2Scalar *m)

Set from a carray of tf2Scalars.

Parameters:

m – A pointer to the beginning of an array of 9 tf2Scalars

inline 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)

Parameters:
  • xx – Top left

  • xy – Top Middle

  • xz – Top Right

  • yx – Middle Left

  • yy – Middle Middle

  • yz – Middle Right

  • zx – Bottom Left

  • zy – Bottom Middle

  • zz – Bottom Right

inline void setRotation(const Quaternion &q)

Set the matrix from a quaternion.

Parameters:

q – The Quaternion to match

inline void setEulerYPR(tf2Scalar eulerZ, tf2Scalar eulerY, tf2Scalar eulerX)

Set the matrix from euler angles YPR around ZYX axes.

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

Parameters:
  • eulerZ – Yaw aboud Z axis

  • eulerY – Pitch around Y axis

  • eulerX – Roll about X axis

inline void setRPY(tf2Scalar roll, tf2Scalar pitch, tf2Scalar yaw)

Set the matrix using RPY about XYZ fixed axes.

Parameters:
  • roll – Roll about X axis

  • pitch – Pitch around Y axis

  • yaw – Yaw aboud Z axis

inline void setIdentity()

Set the matrix to the identity.

inline void getOpenGLSubMatrix(tf2Scalar *m) const

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

Parameters:

m – The array to be filled

inline void getRotation(Quaternion &q) const

Get the matrix represented as a quaternion.

Parameters:

q – The quaternion which will be set

inline 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.

Parameters:
  • yaw – Yaw around Z axis

  • pitch – Pitch around Y axis

  • roll – around X axis

inline 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.

Parameters:
  • roll – around X axis

  • pitch – Pitch around Y axis

  • yaw – Yaw around Z axis

  • solution_number – Which solution of two possible solutions ( 1 or 2) are possible values

inline Matrix3x3 scaled(const Vector3 &s) const

Create a scaled copy of the matrix.

Parameters:

s – Scaling vector The elements of the vector will scale each column

tf2Scalar determinant() const

Return the determinant of the matrix.

Matrix3x3 adjoint() const

Return the adjoint of the matrix.

Matrix3x3 absolute() const

Return the matrix with all values non negative.

Matrix3x3 transpose() const

Return the transpose of the matrix.

Matrix3x3 inverse() const

Return the inverse of the matrix.

Matrix3x3 transposeTimes(const Matrix3x3 &m) const
Matrix3x3 timesTranspose(const Matrix3x3 &m) const
inline tf2Scalar tdotx(const Vector3 &v) const
inline tf2Scalar tdoty(const Vector3 &v) const
inline tf2Scalar tdotz(const Vector3 &v) const
inline void diagonalize(Matrix3x3 &rot, tf2Scalar threshold, int maxSteps)

diagonalizes this matrix by the Jacobi method.

Note that this matrix is assumed to be symmetric.

Parameters:
  • rot – stores 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.

  • threshold – See iteration

  • iteration – The 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.

inline tf2Scalar cofac(int r1, int c1, int r2, int c2) const

Calculate the matrix cofactor.

Parameters:
  • r1 – The first row to use for calculating the cofactor

  • c1 – The first column to use for calculating the cofactor

  • r1 – The second row to use for calculating the cofactor

  • c1 – The second column to use for calculating the cofactor See http://en.wikipedia.org/wiki/Cofactor_(linear_algebra) for more details

void serialize(struct Matrix3x3Data &dataOut) const
void serializeFloat(struct Matrix3x3FloatData &dataOut) const
void deSerialize(const struct Matrix3x3Data &dataIn)
void deSerializeFloat(const struct Matrix3x3FloatData &dataIn)
void deSerializeDouble(const struct Matrix3x3DoubleData &dataIn)

Public Static Functions

static inline const Matrix3x3 &getIdentity()