Gazebo Math

API Reference

8.0.0~pre1

A 4x4 matrix class. More...

#include <gz/math/Matrix4.hh>

Public Member Functions

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

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

Static Public Attributes

static const Matrix4< T > & Identity = detail::gMatrix4Identity<T>
 Identity matrix.
 
static const Matrix4< T > & Zero = detail::gMatrix4Zero<T>
 Zero matrix.
 

Detailed Description

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

A 4x4 matrix class.

Constructor & Destructor Documentation

◆ Matrix4() [1/4]

template<typename T >
Matrix4 ( )
inline

Constructor.

◆ Matrix4() [2/4]

template<typename T >
constexpr Matrix4 ( _v00,
_v01,
_v02,
_v03,
_v10,
_v11,
_v12,
_v13,
_v20,
_v21,
_v22,
_v23,
_v30,
_v31,
_v32,
_v33 
)
inlineconstexpr

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

◆ Matrix4() [3/4]

template<typename T >
Matrix4 ( const Quaternion< T > &  _q)
inlineexplicit

Construct Matrix4 from a quaternion.

Parameters
[in]_qQuaternion.

◆ Matrix4() [4/4]

template<typename T >
Matrix4 ( const Pose3< T > &  _pose)
inlineexplicit

Construct Matrix4 from a math::Pose3.

Parameters
[in]_posePose.

Member Function Documentation

◆ Axis()

template<typename T >
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

◆ Determinant()

template<typename T >
T Determinant ( ) const
inline

Return the determinant of the matrix.

Returns
Determinant of this matrix.

◆ Equal()

template<typename T >
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.

◆ EulerRotation()

template<typename T >
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 GZ_PI.

◆ Inverse()

template<typename T >
Matrix4< T > Inverse ( ) const
inline

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

Returns
Inverse of this matrix.

◆ IsAffine()

template<typename T >
bool IsAffine ( ) const
inline

Return true if the matrix is affine.

Returns
true if the matrix is affine, false otherwise

References gz::math::equal().

◆ LookAt()

template<typename T >
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 Vector3< T >::Normalize().

◆ operator!=()

template<typename T >
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]

template<typename T >
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 gz::math::clamp(), gz::math::GZ_THREE_SIZE_T, and gz::math::GZ_ZERO_SIZE_T.

◆ operator()() [2/2]

template<typename T >
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 gz::math::clamp(), gz::math::GZ_THREE_SIZE_T, and gz::math::GZ_ZERO_SIZE_T.

◆ operator*() [1/2]

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

Multiplication operator.

Parameters
[in]_m2Incoming matrix
Returns
This matrix * _mat

◆ operator*() [2/2]

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

Multiplication operator.

Parameters
_vecVector3
Returns
Resulting vector from multiplication

◆ operator*=()

template<typename T >
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=()

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

Equal operator for 3x3 matrix.

Parameters
_matIncoming matrix
Returns
itself

◆ operator==()

template<typename T >
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

◆ Pose()

template<typename T >
Pose3< T > Pose ( ) const
inline

Get the transformation as math::Pose.

Returns
the pose

◆ Rotation()

template<typename T >
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 Calculus and Fast Animation".

◆ Scale() [1/3]

template<typename T >
Vector3< T > Scale ( ) const
inline

Get the scale values as a Vector3<T>

Returns
x,y,z scale values

◆ Scale() [2/3]

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

Set the scale.

Parameters
[in]_sscale

◆ Scale() [3/3]

template<typename T >
void Scale ( _x,
_y,
_z 
)
inline

Set the scale.

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

◆ Set()

template<typename T >
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

◆ SetTranslation() [1/2]

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

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

Parameters
[in]_tValues to set

◆ SetTranslation() [2/2]

template<typename T >
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()

template<typename T >
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 Matrix6< T >::Set().

◆ Translation()

template<typename T >
Vector3< T > Translation ( ) const
inline

Get the translational values as a Vector3.

Returns
x,y,z translation values

◆ Transpose()

template<typename T >
void Transpose ( )
inline

Transpose this matrix.

References std::swap().

◆ Transposed()

template<typename T >
Matrix4< T > Transposed ( ) const
inline

Return the transpose of this matrix.

Returns
Transpose of this matrix.

Member Data Documentation

◆ Identity

template<typename T >
const Matrix4< T > & Identity = detail::gMatrix4Identity<T>
static

Identity matrix.

◆ Zero

template<typename T >
const Matrix4< T > & Zero = detail::gMatrix4Zero<T>
static

Zero matrix.


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