Public Member Functions | Static Public Attributes | Protected Attributes | Friends | List of all members
gazebo::math::Matrix4 Class Reference

A 3x3 matrix class. More...

#include <math/gzmath.hh>

Public Member Functions

 Matrix4 ()
 Constructor. More...
 
 Matrix4 (const Matrix4 &_m)
 Copy constructor. More...
 
 Matrix4 (double _v00, double _v01, double _v02, double _v03, double _v10, double _v11, double _v12, double _v13, double _v20, double _v21, double _v22, double _v23, double _v30, double _v31, double _v32, double _v33)
 Constructor. More...
 
virtual ~Matrix4 ()
 Destructor. More...
 
math::Pose GetAsPose () const
 Get the transformation as math::Pose. More...
 
Vector3 GetEulerRotation (unsigned int solution_number=1) const
 Get the rotation as a Euler angles. More...
 
Quaternion GetRotation () const
 Get the rotation as a quaternion. More...
 
Vector3 GetTranslation () const
 Get the translational values as a Vector3. More...
 
Matrix4 Inverse () const
 Return the inverse matrix. More...
 
bool IsAffine () const
 Return true if the matrix is affine. More...
 
Matrix4 operator* (const Matrix4 &_mat) const
 Multiplication operator. More...
 
Matrix4 operator* (const Matrix3 &_mat) const
 Multiplication operator. More...
 
Vector3 operator* (const Vector3 &_vec) const
 Multiplication operator. More...
 
Matrix4operator= (const Matrix4 &_mat)
 Equal operator. More...
 
const Matrix4operator= (const Matrix3 &_mat)
 Equal operator for 3x3 matrix. More...
 
bool operator== (const Matrix4 &_m) const
 Equality operator. More...
 
double * operator[] (size_t _row)
 Array subscript operator. More...
 
const double * operator[] (size_t _row) const
 
void Set (double _v00, double _v01, double _v02, double _v03, double _v10, double _v11, double _v12, double _v13, double _v20, double _v21, double _v22, double _v23, double _v30, double _v31, double _v32, double _v33)
 Change the values. More...
 
void SetScale (const Vector3 &_s)
 Set the scale. More...
 
void SetTranslate (const Vector3 &_t)
 Set the translational values [ (0, 3) (1, 3) (2, 3) ]. More...
 
Vector3 TransformAffine (const Vector3 &_v) const
 Perform an affine transformation. More...
 

Static Public Attributes

static const Matrix4 IDENTITY
 Identity matrix. More...
 
static const Matrix4 ZERO
 Zero matrix. More...
 

Protected Attributes

double m [4][4]
 The 4x4 matrix. More...
 

Friends

std::ostream & operator<< (std::ostream &_out, const gazebo::math::Matrix4 &_m)
 Stream insertion operator. More...
 

Detailed Description

A 3x3 matrix class.

Constructor & Destructor Documentation

gazebo::math::Matrix4::Matrix4 ( )

Constructor.

gazebo::math::Matrix4::Matrix4 ( const Matrix4 _m)

Copy constructor.

Parameters
_mMatrix to copy
gazebo::math::Matrix4::Matrix4 ( double  _v00,
double  _v01,
double  _v02,
double  _v03,
double  _v10,
double  _v11,
double  _v12,
double  _v13,
double  _v20,
double  _v21,
double  _v22,
double  _v23,
double  _v30,
double  _v31,
double  _v32,
double  _v33 
)

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
virtual gazebo::math::Matrix4::~Matrix4 ( )
virtual

Destructor.

Member Function Documentation

math::Pose gazebo::math::Matrix4::GetAsPose ( ) const

Get the transformation as math::Pose.

Returns
the pose
Vector3 gazebo::math::Matrix4::GetEulerRotation ( unsigned int  solution_number = 1) const

Get the rotation as a Euler angles.

Returns
the rotation
Quaternion gazebo::math::Matrix4::GetRotation ( ) const

Get the rotation as a quaternion.

Returns
the rotation
Vector3 gazebo::math::Matrix4::GetTranslation ( ) const

Get the translational values as a Vector3.

Returns
x,y,z
Matrix4 gazebo::math::Matrix4::Inverse ( ) const

Return the inverse matrix.

bool gazebo::math::Matrix4::IsAffine ( ) const

Return true if the matrix is affine.

Returns
true if the matrix is affine, false otherwise
Matrix4 gazebo::math::Matrix4::operator* ( const Matrix4 _mat) const

Multiplication operator.

Parameters
_matIncoming matrix
Returns
This matrix * _mat
Matrix4 gazebo::math::Matrix4::operator* ( const Matrix3 _mat) const

Multiplication operator.

Parameters
_matIncoming matrix
Returns
This matrix * _mat
Vector3 gazebo::math::Matrix4::operator* ( const Vector3 _vec) const

Multiplication operator.

Parameters
_vecVector3
Returns
Resulting vector from multiplication
Matrix4& gazebo::math::Matrix4::operator= ( const Matrix4 _mat)

Equal operator.

this = _mat

Parameters
_matIncoming matrix
Returns
itself
const Matrix4& gazebo::math::Matrix4::operator= ( const Matrix3 _mat)

Equal operator for 3x3 matrix.

Parameters
_matIncoming matrix
Returns
itself
bool gazebo::math::Matrix4::operator== ( const Matrix4 _m) const

Equality operator.

Parameters
[in]_mMatrix3 to test
Returns
true if the 2 matrices are equal (using the tolerance 1e-6), false otherwise
double* gazebo::math::Matrix4::operator[] ( size_t  _row)
inline

Array subscript operator.

Parameters
[in]_rowthe row index
Returns
the row
const double* gazebo::math::Matrix4::operator[] ( size_t  _row) const
inline
Parameters
[in]_rowthe row index
Returns
the row
void gazebo::math::Matrix4::Set ( double  _v00,
double  _v01,
double  _v02,
double  _v03,
double  _v10,
double  _v11,
double  _v12,
double  _v13,
double  _v20,
double  _v21,
double  _v22,
double  _v23,
double  _v30,
double  _v31,
double  _v32,
double  _v33 
)

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
void gazebo::math::Matrix4::SetScale ( const Vector3 _s)

Set the scale.

Parameters
[in]_sscale
void gazebo::math::Matrix4::SetTranslate ( const Vector3 _t)

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

Parameters
[in]_tValues to set
Vector3 gazebo::math::Matrix4::TransformAffine ( const Vector3 _v) const

Perform an affine transformation.

Parameters
_vVector3 value for the transformation
Returns
The result of the transformation

Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  _out,
const gazebo::math::Matrix4 _m 
)
friend

Stream insertion operator.

Parameters
_outoutput stream
_mMatrix to output
Returns
the stream

Member Data Documentation

const Matrix4 gazebo::math::Matrix4::IDENTITY
static

Identity matrix.

double gazebo::math::Matrix4::m[4][4]
protected

The 4x4 matrix.

const Matrix4 gazebo::math::Matrix4::ZERO
static

Zero matrix.


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