Public Member Functions | Static Public Member Functions | Private Attributes | List of all members
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>

Public Member Functions

Matrix3x3 absolute () const
 Return the matrix with all values non negative. More...
 
Matrix3x3 adjoint () const
 Return the adjoint of the matrix. More...
 
tf2Scalar cofac (int r1, int c1, int r2, int c2) const
 Calculate the matrix cofactor. More...
 
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. More...
 
void diagonalize (Matrix3x3 &rot, tf2Scalar threshold, int maxSteps)
 diagonalizes this matrix by the Jacobi method. More...
 
TF2SIMD_FORCE_INLINE Vector3 getColumn (int i) const
 Get a column of the matrix as a vector. More...
 
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. More...
 
ROS_DEPRECATED void getEulerZYX (tf2Scalar &yaw, tf2Scalar &pitch, tf2Scalar &roll, unsigned int solution_number=1) const
 Get the matrix represented as euler angles around ZYX. More...
 
void getOpenGLSubMatrix (tf2Scalar *m) const
 Fill the values of the matrix into a 9 element array. More...
 
void getRotation (Quaternion &q) const
 Get the matrix represented as a quaternion. More...
 
const TF2SIMD_FORCE_INLINE Vector3 & getRow (int i) const
 Get a row of the matrix as a vector. More...
 
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. More...
 
Matrix3x3 inverse () const
 Return the inverse of the matrix. More...
 
 Matrix3x3 ()
 No initializaion constructor. More...
 
TF2SIMD_FORCE_INLINE Matrix3x3 (const Matrix3x3 &other)
 Copy constructor. More...
 
 Matrix3x3 (const Quaternion &q)
 Constructor from Quaternion. More...
 
 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. More...
 
Matrix3x3operator*= (const Matrix3x3 &m)
 Multiply by the target matrix on the right. More...
 
TF2SIMD_FORCE_INLINE Matrix3x3operator= (const Matrix3x3 &other)
 Assignment Operator. More...
 
TF2SIMD_FORCE_INLINE Vector3 & operator[] (int i)
 Get a mutable reference to a row of the matrix as a vector. More...
 
const TF2SIMD_FORCE_INLINE Vector3 & operator[] (int i) const
 Get a const reference to a row of the matrix as a vector. More...
 
Matrix3x3 scaled (const Vector3 &s) const
 Create a scaled copy of the matrix. More...
 
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. More...
 
ROS_DEPRECATED void setEulerZYX (const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
 Set the matrix from euler angles using YPR around ZYX respectively. More...
 
void setFromOpenGLSubMatrix (const tf2Scalar *m)
 Set from a carray of tf2Scalars. More...
 
void setIdentity ()
 Set the matrix to the identity. More...
 
void setRotation (const Quaternion &q)
 Set the matrix from a quaternion. More...
 
void setRPY (tf2Scalar roll, tf2Scalar pitch, tf2Scalar yaw)
 Set the matrix using RPY about XYZ fixed axes. More...
 
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) More...
 
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. More...
 
Matrix3x3 transposeTimes (const Matrix3x3 &m) const
 

Static Public Member Functions

static const Matrix3x3getIdentity ()
 

Private Attributes

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

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 33 of file Matrix3x3.h.

Constructor & Destructor Documentation

◆ Matrix3x3() [1/4]

tf2::Matrix3x3::Matrix3x3 ( )
inline

No initializaion constructor.

Definition at line 40 of file Matrix3x3.h.

◆ Matrix3x3() [2/4]

tf2::Matrix3x3::Matrix3x3 ( const Quaternion q)
inlineexplicit

Constructor from Quaternion.

Definition at line 45 of file Matrix3x3.h.

◆ Matrix3x3() [3/4]

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 54 of file Matrix3x3.h.

◆ Matrix3x3() [4/4]

TF2SIMD_FORCE_INLINE tf2::Matrix3x3::Matrix3x3 ( const Matrix3x3 other)
inline

Copy constructor.

Definition at line 63 of file Matrix3x3.h.

Member Function Documentation

◆ absolute()

TF2SIMD_FORCE_INLINE Matrix3x3 tf2::Matrix3x3::absolute ( ) const

Return the matrix with all values non negative.

Definition at line 541 of file Matrix3x3.h.

◆ adjoint()

TF2SIMD_FORCE_INLINE Matrix3x3 tf2::Matrix3x3::adjoint ( ) const

Return the adjoint of the matrix.

Definition at line 558 of file Matrix3x3.h.

◆ cofac()

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 506 of file Matrix3x3.h.

◆ deSerialize()

TF2SIMD_FORCE_INLINE void tf2::Matrix3x3::deSerialize ( const struct Matrix3x3Data dataIn)

Definition at line 676 of file Matrix3x3.h.

◆ deSerializeDouble()

TF2SIMD_FORCE_INLINE void tf2::Matrix3x3::deSerializeDouble ( const struct Matrix3x3DoubleData dataIn)

Definition at line 688 of file Matrix3x3.h.

◆ deSerializeFloat()

TF2SIMD_FORCE_INLINE void tf2::Matrix3x3::deSerializeFloat ( const struct Matrix3x3FloatData dataIn)

Definition at line 682 of file Matrix3x3.h.

◆ determinant()

TF2SIMD_FORCE_INLINE tf2Scalar tf2::Matrix3x3::determinant ( ) const

Return the determinant of the matrix.

Definition at line 534 of file Matrix3x3.h.

◆ diagonalize()

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 418 of file Matrix3x3.h.

◆ getColumn()

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 83 of file Matrix3x3.h.

◆ getEulerYPR()

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 294 of file Matrix3x3.h.

◆ getEulerZYX()

ROS_DEPRECATED void tf2::Matrix3x3::getEulerZYX ( tf2Scalar yaw,
tf2Scalar pitch,
tf2Scalar roll,
unsigned int  solution_number = 1 
) const
inline

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

Definition at line 284 of file Matrix3x3.h.

◆ getIdentity()

static const Matrix3x3& tf2::Matrix3x3::getIdentity ( )
inlinestatic

Definition at line 217 of file Matrix3x3.h.

◆ getOpenGLSubMatrix()

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 227 of file Matrix3x3.h.

◆ getRotation()

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 245 of file Matrix3x3.h.

◆ getRow()

const TF2SIMD_FORCE_INLINE 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 91 of file Matrix3x3.h.

◆ getRPY()

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 366 of file Matrix3x3.h.

◆ inverse()

TF2SIMD_FORCE_INLINE Matrix3x3 tf2::Matrix3x3::inverse ( ) const

Return the inverse of the matrix.

Definition at line 566 of file Matrix3x3.h.

◆ operator*=()

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 525 of file Matrix3x3.h.

◆ operator=()

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

Assignment Operator.

Definition at line 72 of file Matrix3x3.h.

◆ operator[]() [1/2]

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 99 of file Matrix3x3.h.

◆ operator[]() [2/2]

const TF2SIMD_FORCE_INLINE 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 107 of file Matrix3x3.h.

◆ scaled()

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 374 of file Matrix3x3.h.

◆ serialize()

TF2SIMD_FORCE_INLINE void tf2::Matrix3x3::serialize ( struct Matrix3x3Data dataOut) const

Definition at line 663 of file Matrix3x3.h.

◆ serializeFloat()

TF2SIMD_FORCE_INLINE void tf2::Matrix3x3::serializeFloat ( struct Matrix3x3FloatData dataOut) const

Definition at line 669 of file Matrix3x3.h.

◆ setEulerYPR()

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 182 of file Matrix3x3.h.

◆ setEulerZYX()

ROS_DEPRECATED 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 168 of file Matrix3x3.h.

◆ setFromOpenGLSubMatrix()

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 120 of file Matrix3x3.h.

◆ setIdentity()

void tf2::Matrix3x3::setIdentity ( )
inline

Set the matrix to the identity.

Definition at line 210 of file Matrix3x3.h.

◆ setRotation()

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

Set the matrix from a quaternion.

Parameters
qThe Quaternion to match

Definition at line 148 of file Matrix3x3.h.

◆ setRPY()

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 205 of file Matrix3x3.h.

◆ setValue()

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 137 of file Matrix3x3.h.

◆ tdotx()

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

Definition at line 395 of file Matrix3x3.h.

◆ tdoty()

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

Definition at line 399 of file Matrix3x3.h.

◆ tdotz()

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

Definition at line 403 of file Matrix3x3.h.

◆ timesTranspose()

TF2SIMD_FORCE_INLINE Matrix3x3 tf2::Matrix3x3::timesTranspose ( const Matrix3x3 m) const

Definition at line 593 of file Matrix3x3.h.

◆ transpose()

TF2SIMD_FORCE_INLINE Matrix3x3 tf2::Matrix3x3::transpose ( ) const

Return the transpose of the matrix.

Definition at line 550 of file Matrix3x3.h.

◆ transposeTimes()

TF2SIMD_FORCE_INLINE Matrix3x3 tf2::Matrix3x3::transposeTimes ( const Matrix3x3 m) const

Definition at line 578 of file Matrix3x3.h.

Member Data Documentation

◆ m_el

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

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

Definition at line 36 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 Sun Feb 4 2024 03:18:11