Ignition Math

API Reference

6.10.0

A 4x4 matrix class. More...

#include <ignition/math/Matrix4.hh>

Public Member Functions

 Matrix4 ()
 Constructor. More...
 
 Matrix4 (const Matrix4< T > &_m)
 Copy constructor. More...
 
 Matrix4 (T _v00, T _v01, T _v02, T _v03, T _v10, T _v11, T _v12, T _v13, T _v20, T _v21, T _v22, T _v23, T _v30, T _v31, T _v32, T _v33)
 Constructor. More...
 
 Matrix4 (const Quaternion< T > &_q)
 Construct Matrix4 from a quaternion. More...
 
 Matrix4 (const Pose3< T > &_pose)
 Construct Matrix4 from a math::Pose3. More...
 
virtual ~Matrix4 ()
 Destructor. More...
 
void Axis (const Vector3< T > &_axis, T _angle)
 Set the upper-left 3x3 matrix from an axis and angle. More...
 
Determinant () const
 Return the determinant of the matrix. More...
 
bool Equal (const Matrix4 &_m, const T &_tol) const
 Equality test with tolerance. More...
 
Vector3< T > EulerRotation (bool _firstSolution) const
 Get the rotation as a Euler angles. More...
 
Matrix4< T > Inverse () const
 Return the inverse matrix. This is a non-destructive operation. More...
 
bool IsAffine () const
 Return true if the matrix is affine. More...
 
bool operator!= (const Matrix4< T > &_m) const
 Inequality test operator. More...
 
const T & operator() (const size_t _row, const size_t _col) const
 Get the value at the specified row, column index. More...
 
T & operator() (const size_t _row, const size_t _col)
 Get a mutable version the value at the specified row, column index. More...
 
Matrix4< T > operator* (const Matrix4< T > &_m2) const
 Multiplication operator. More...
 
Vector3< T > operator* (const Vector3< T > &_vec) const
 Multiplication operator. More...
 
Matrix4< T > operator*= (const Matrix4< T > &_m2)
 Multiplication assignment operator. This matrix will become equal to this * _m2. More...
 
Matrix4< T > & operator= (const Matrix4< T > &_mat)
 Equal operator. this = _mat. More...
 
const Matrix4< T > & operator= (const Matrix3< T > &_mat)
 Equal operator for 3x3 matrix. More...
 
bool operator== (const Matrix4< T > &_m) const
 Equality operator. More...
 
Pose3< T > Pose () const
 Get the transformation as math::Pose. More...
 
Quaternion< T > Rotation () const
 Get the rotation as a quaternion. More...
 
Vector3< T > Scale () const
 Get the scale values as a Vector3<T> More...
 
void Scale (const Vector3< T > &_s)
 Set the scale. More...
 
void Scale (T _x, T _y, T _z)
 Set the scale. More...
 
void Set (T _v00, T _v01, T _v02, T _v03, T _v10, T _v11, T _v12, T _v13, T _v20, T _v21, T _v22, T _v23, T _v30, T _v31, T _v32, T _v33)
 Change the values. More...
 
void SetTranslation (const Vector3< T > &_t)
 Set the translational values [ (0, 3) (1, 3) (2, 3) ]. More...
 
void SetTranslation (T _x, T _y, T _z)
 Set the translational values [ (0, 3) (1, 3) (2, 3) ]. More...
 
Vector3< T > TransformAffine (const Vector3< T > &_v) const
 Perform an affine transformation. More...
 
bool TransformAffine (const Vector3< T > &_v, Vector3< T > &_result) const
 Perform an affine transformation. More...
 
void Translate (const Vector3< T > &_t)
 Set the translational values [ (0, 3) (1, 3) (2, 3) ]. More...
 
void Translate (T _x, T _y, T _z)
 Set the translational values [ (0, 3) (1, 3) (2, 3) ]. More...
 
Vector3< T > Translation () const
 Get the translational values as a Vector3. More...
 
void Transpose ()
 Transpose this matrix. More...
 
Matrix4< T > Transposed () const
 Return the transpose of this matrix. More...
 

Static Public Member Functions

static Matrix4< T > LookAt (const Vector3< T > &_eye, const Vector3< T > &_target, const Vector3< T > &_up=Vector3< T >::UnitZ)
 Get transform which translates to _eye and rotates the X axis so it faces the _target. The rotation is such that Z axis is in the _up direction, if possible. The coordinate system is right-handed,. More...
 

Static Public Attributes

static const Matrix4< T > Identity
 Identity matrix. More...
 
static const Matrix4< T > Zero
 Zero matrix. More...
 

Friends

std::ostreamoperator<< (std::ostream &_out, const Matrix4< T > &_m)
 Stream insertion operator. More...
 
std::istreamoperator>> (std::istream &_in, Matrix4< T > &_m)
 Stream extraction operator. More...
 

Detailed Description

template<typename T>
class ignition::math::Matrix4< T >

A 4x4 matrix class.

Constructor & Destructor Documentation

◆ Matrix4() [1/5]

Matrix4 ( )
inline

Constructor.

◆ Matrix4() [2/5]

Matrix4 ( const Matrix4< T > &  _m)
inline

Copy constructor.

Parameters
_mMatrix to copy

◆ Matrix4() [3/5]

Matrix4 ( _v00,
_v01,
_v02,
_v03,
_v10,
_v11,
_v12,
_v13,
_v20,
_v21,
_v22,
_v23,
_v30,
_v31,
_v32,
_v33 
)
inline

Constructor.

Parameters
[in]_v00Row 0, Col 0 value
[in]_v01Row 0, Col 1 value
[in]_v02Row 0, Col 2 value
[in]_v03Row 0, Col 3 value
[in]_v10Row 1, Col 0 value
[in]_v11Row 1, Col 1 value
[in]_v12Row 1, Col 2 value
[in]_v13Row 1, Col 3 value
[in]_v20Row 2, Col 0 value
[in]_v21Row 2, Col 1 value
[in]_v22Row 2, Col 2 value
[in]_v23Row 2, Col 3 value
[in]_v30Row 3, Col 0 value
[in]_v31Row 3, Col 1 value
[in]_v32Row 3, Col 2 value
[in]_v33Row 3, Col 3 value

References Matrix4< T >::Set().

◆ Matrix4() [4/5]

Matrix4 ( const Quaternion< T > &  _q)
inlineexplicit

◆ Matrix4() [5/5]

Matrix4 ( const Pose3< T > &  _pose)
inlineexplicit

Construct Matrix4 from a math::Pose3.

Parameters
[in]_posePose.

References Pose3< T >::Pos(), and Matrix4< T >::SetTranslation().

◆ ~Matrix4()

virtual ~Matrix4 ( )
inlinevirtual

Destructor.

Member Function Documentation

◆ Axis()

void Axis ( const Vector3< T > &  _axis,
_angle 
)
inline

Set the upper-left 3x3 matrix from an axis and angle.

Parameters
[in]_axisthe axis
[in]_angleccw rotation around the axis in radians

References Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().

◆ Determinant()

T Determinant ( ) const
inline

Return the determinant of the matrix.

Returns
Determinant of this matrix.

◆ Equal()

bool Equal ( const Matrix4< T > &  _m,
const T &  _tol 
) const
inline

Equality test with tolerance.

Parameters
[in]_mthe matrix to compare to
[in]_tolequality tolerance.
Returns
true if the elements of the matrices are equal within the tolerence specified by _tol.

Referenced by Matrix4< T >::operator==().

◆ EulerRotation()

Vector3<T> EulerRotation ( bool  _firstSolution) const
inline

Get the rotation as a Euler angles.

Parameters
[in]_firstSolutionTrue to get the first Euler solution, false to get the second.
Returns
the rotation

References IGN_PI, Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().

◆ Inverse()

Matrix4<T> Inverse ( ) const
inline

Return the inverse matrix. This is a non-destructive operation.

Returns
Inverse of this matrix.

◆ IsAffine()

bool IsAffine ( ) const
inline

Return true if the matrix is affine.

Returns
true if the matrix is affine, false otherwise

References ignition::math::equal().

Referenced by Matrix4< T >::TransformAffine().

◆ LookAt()

static Matrix4<T> LookAt ( const Vector3< T > &  _eye,
const Vector3< T > &  _target,
const Vector3< T > &  _up = Vector3<T>::UnitZ 
)
inlinestatic

Get transform which translates to _eye and rotates the X axis so it faces the _target. The rotation is such that Z axis is in the _up direction, if possible. The coordinate system is right-handed,.

Parameters
[in]_eyeCoordinate frame translation.
[in]_targetPoint which the X axis should face. If _target is equal to _eye, the X axis won't be rotated.
[in]_upDirection in which the Z axis should point. If _up is zero or parallel to X, it will be set to +Z.
Returns
Transformation matrix.

References Matrix4< T >::Identity, Vector3< T >::Normalize(), and Matrix4< T >::Zero.

◆ operator!=()

bool operator!= ( const Matrix4< T > &  _m) const
inline

Inequality test operator.

Parameters
[in]_mMatrix4<T> to test
Returns
True if not equal (using the default tolerance of 1e-6)

◆ operator()() [1/2]

const T& operator() ( const size_t  _row,
const size_t  _col 
) const
inline

Get the value at the specified row, column index.

Parameters
[in]_colThe column index. Index values are clamped to a range of [0, 3].
[in]_rowthe row index. Index values are clamped to a range of [0, 3].
Returns
The value at the specified index

References ignition::math::clamp(), ignition::math::IGN_THREE_SIZE_T, and ignition::math::IGN_ZERO_SIZE_T.

◆ operator()() [2/2]

T& operator() ( const size_t  _row,
const size_t  _col 
)
inline

Get a mutable version the value at the specified row, column index.

Parameters
[in]_colThe column index. Index values are clamped to a range of [0, 3].
[in]_rowthe row index. Index values are clamped to a range of [0, 3].
Returns
The value at the specified index

References ignition::math::clamp(), ignition::math::IGN_THREE_SIZE_T, and ignition::math::IGN_ZERO_SIZE_T.

◆ operator*() [1/2]

Matrix4<T> operator* ( const Matrix4< T > &  _m2) const
inline

Multiplication operator.

Parameters
[in]_m2Incoming matrix
Returns
This matrix * _mat

◆ operator*() [2/2]

Vector3<T> operator* ( const Vector3< T > &  _vec) const
inline

Multiplication operator.

Parameters
_vecVector3
Returns
Resulting vector from multiplication

References Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().

◆ operator*=()

Matrix4<T> operator*= ( const Matrix4< T > &  _m2)
inline

Multiplication assignment operator. This matrix will become equal to this * _m2.

Parameters
[in]_m2Incoming matrix.
Returns
This matrix * _mat.

◆ operator=() [1/2]

Matrix4<T>& operator= ( const Matrix4< T > &  _mat)
inline

Equal operator. this = _mat.

Parameters
_matIncoming matrix
Returns
itself

◆ operator=() [2/2]

const Matrix4<T>& operator= ( const Matrix3< T > &  _mat)
inline

Equal operator for 3x3 matrix.

Parameters
_matIncoming matrix
Returns
itself

◆ operator==()

bool operator== ( const Matrix4< T > &  _m) const
inline

Equality operator.

Parameters
[in]_mMatrix3 to test
Returns
true if the 2 matrices are equal (using the tolerance 1e-6), false otherwise

References Matrix4< T >::Equal().

◆ Pose()

Pose3<T> Pose ( ) const
inline

Get the transformation as math::Pose.

Returns
the pose

References Matrix4< T >::Rotation(), and Matrix4< T >::Translation().

◆ Rotation()

Quaternion<T> Rotation ( ) const
inline

Get the rotation as a quaternion.

Returns
the rotation

algorithm from Ogre::Quaternion<T> source, which in turn is based on Ken Shoemake's article "Quaternion<T> Calculus and Fast Animation".

References Quaternion< T >::W(), Quaternion< T >::X(), Quaternion< T >::Y(), and Quaternion< T >::Z().

Referenced by Matrix4< T >::Pose().

◆ Scale() [1/3]

Vector3<T> Scale ( ) const
inline

Get the scale values as a Vector3<T>

Returns
x,y,z scale values

◆ Scale() [2/3]

void Scale ( const Vector3< T > &  _s)
inline

Set the scale.

Parameters
[in]_sscale

References Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().

◆ Scale() [3/3]

void Scale ( _x,
_y,
_z 
)
inline

Set the scale.

Parameters
[in]_xX scale value.
[in]_yY scale value.
[in]_zZ scale value.

◆ Set()

void Set ( _v00,
_v01,
_v02,
_v03,
_v10,
_v11,
_v12,
_v13,
_v20,
_v21,
_v22,
_v23,
_v30,
_v31,
_v32,
_v33 
)
inline

Change the values.

Parameters
[in]_v00Row 0, Col 0 value
[in]_v01Row 0, Col 1 value
[in]_v02Row 0, Col 2 value
[in]_v03Row 0, Col 3 value
[in]_v10Row 1, Col 0 value
[in]_v11Row 1, Col 1 value
[in]_v12Row 1, Col 2 value
[in]_v13Row 1, Col 3 value
[in]_v20Row 2, Col 0 value
[in]_v21Row 2, Col 1 value
[in]_v22Row 2, Col 2 value
[in]_v23Row 2, Col 3 value
[in]_v30Row 3, Col 0 value
[in]_v31Row 3, Col 1 value
[in]_v32Row 3, Col 2 value
[in]_v33Row 3, Col 3 value

Referenced by Matrix4< T >::Matrix4().

◆ SetTranslation() [1/2]

void SetTranslation ( const Vector3< T > &  _t)
inline

Set the translational values [ (0, 3) (1, 3) (2, 3) ].

Parameters
[in]_tValues to set

References Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().

Referenced by Matrix4< T >::Matrix4(), and Matrix4< T >::Translate().

◆ SetTranslation() [2/2]

void SetTranslation ( _x,
_y,
_z 
)
inline

Set the translational values [ (0, 3) (1, 3) (2, 3) ].

Parameters
[in]_xX translation value.
[in]_yY translation value.
[in]_zZ translation value.

◆ TransformAffine() [1/2]

Vector3<T> TransformAffine ( const Vector3< T > &  _v) const
inline

Perform an affine transformation.

Parameters
[in]_vVector3 value for the transformation
Returns
The result of the transformation. A default constructed Vector3<T> is returned if this matrix is not affine.
Deprecated:
Use bool TransformAffine(const Vector3<T> &_v, Vector3<T> &_result) const;

References Matrix4< T >::IsAffine(), Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().

◆ TransformAffine() [2/2]

bool TransformAffine ( const Vector3< T > &  _v,
Vector3< T > &  _result 
) const
inline

Perform an affine transformation.

Parameters
[in]_vVector3 value for the transformation
[out]_resultThe result of the transformation. _result is not changed if this matrix is not affine.
Returns
True if this matrix is affine, false otherwise.

References Matrix4< T >::IsAffine(), Vector3< T >::Set(), Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().

◆ Translate() [1/2]

void Translate ( const Vector3< T > &  _t)
inline

Set the translational values [ (0, 3) (1, 3) (2, 3) ].

Parameters
[in]_tValues to set
Deprecated:
Use SetTranslation instead

References Matrix4< T >::SetTranslation().

◆ Translate() [2/2]

void Translate ( _x,
_y,
_z 
)
inline

Set the translational values [ (0, 3) (1, 3) (2, 3) ].

Parameters
[in]_xX translation value.
[in]_yY translation value.
[in]_zZ translation value.
Deprecated:
Use SetTranslation instead

References Matrix4< T >::SetTranslation().

◆ Translation()

Vector3<T> Translation ( ) const
inline

Get the translational values as a Vector3.

Returns
x,y,z translation values

Referenced by Matrix4< T >::Pose().

◆ Transpose()

void Transpose ( )
inline

Transpose this matrix.

References std::swap().

◆ Transposed()

Matrix4<T> Transposed ( ) const
inline

Return the transpose of this matrix.

Returns
Transpose of this matrix.

Friends And Related Function Documentation

◆ operator<<

std::ostream& operator<< ( std::ostream _out,
const Matrix4< T > &  _m 
)
friend

Stream insertion operator.

Parameters
_outoutput stream
_mMatrix to output
Returns
the stream

◆ operator>>

std::istream& operator>> ( std::istream _in,
Matrix4< T > &  _m 
)
friend

Stream extraction operator.

Parameters
[in,out]_ininput stream
[out]_mMatrix4<T> to read values into
Returns
the stream

Member Data Documentation

◆ Identity

const Matrix4< T > Identity
static

Identity matrix.

Referenced by Matrix4< T >::LookAt().

◆ Zero

const Matrix4< T > Zero
static

Zero matrix.

Referenced by Matrix4< T >::LookAt().


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