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... | |
| Matrix4 & | operator= (const Matrix4 &_mat) | 
| Equal operator.  More... | |
| const Matrix4 & | operator= (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... | |
A 3x3 matrix class.
| gazebo::math::Matrix4::Matrix4 | ( | ) | 
Constructor.
| gazebo::math::Matrix4::Matrix4 | ( | const Matrix4 & | _m | ) | 
Copy constructor.
| _m | Matrix 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.
| [in] | _v00 | Row 0, Col 0 value | 
| [in] | _v01 | Row 0, Col 1 value | 
| [in] | _v02 | Row 0, Col 2 value | 
| [in] | _v03 | Row 0, Col 3 value | 
| [in] | _v10 | Row 1, Col 0 value | 
| [in] | _v11 | Row 1, Col 1 value | 
| [in] | _v12 | Row 1, Col 2 value | 
| [in] | _v13 | Row 1, Col 3 value | 
| [in] | _v20 | Row 2, Col 0 value | 
| [in] | _v21 | Row 2, Col 1 value | 
| [in] | _v22 | Row 2, Col 2 value | 
| [in] | _v23 | Row 2, Col 3 value | 
| [in] | _v30 | Row 3, Col 0 value | 
| [in] | _v31 | Row 3, Col 1 value | 
| [in] | _v32 | Row 3, Col 2 value | 
| [in] | _v33 | Row 3, Col 3 value | 
| 
 | virtual | 
Destructor.
| math::Pose gazebo::math::Matrix4::GetAsPose | ( | ) | const | 
Get the transformation as math::Pose.
| Vector3 gazebo::math::Matrix4::GetEulerRotation | ( | unsigned int | solution_number = 1 | ) | const | 
Get the rotation as a Euler angles.
| Quaternion gazebo::math::Matrix4::GetRotation | ( | ) | const | 
Get the rotation as a quaternion.
| Vector3 gazebo::math::Matrix4::GetTranslation | ( | ) | const | 
Get the translational values as a Vector3.
| Matrix4 gazebo::math::Matrix4::Inverse | ( | ) | const | 
Return the inverse matrix.
| bool gazebo::math::Matrix4::IsAffine | ( | ) | const | 
Return true if the matrix is affine.
Multiplication operator.
| _mat | Incoming matrix | 
Multiplication operator.
| _mat | Incoming matrix | 
Equal operator.
this = _mat
| _mat | Incoming matrix | 
Equal operator for 3x3 matrix.
| _mat | Incoming matrix | 
| bool gazebo::math::Matrix4::operator== | ( | const Matrix4 & | _m | ) | const | 
Equality operator.
| [in] | _m | Matrix3 to test | 
| 
 | inline | 
| 
 | inline | 
| 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.
| [in] | _v00 | Row 0, Col 0 value | 
| [in] | _v01 | Row 0, Col 1 value | 
| [in] | _v02 | Row 0, Col 2 value | 
| [in] | _v03 | Row 0, Col 3 value | 
| [in] | _v10 | Row 1, Col 0 value | 
| [in] | _v11 | Row 1, Col 1 value | 
| [in] | _v12 | Row 1, Col 2 value | 
| [in] | _v13 | Row 1, Col 3 value | 
| [in] | _v20 | Row 2, Col 0 value | 
| [in] | _v21 | Row 2, Col 1 value | 
| [in] | _v22 | Row 2, Col 2 value | 
| [in] | _v23 | Row 2, Col 3 value | 
| [in] | _v30 | Row 3, Col 0 value | 
| [in] | _v31 | Row 3, Col 1 value | 
| [in] | _v32 | Row 3, Col 2 value | 
| [in] | _v33 | Row 3, Col 3 value | 
| void gazebo::math::Matrix4::SetScale | ( | const Vector3 & | _s | ) | 
Set the scale.
| [in] | _s | scale | 
| void gazebo::math::Matrix4::SetTranslate | ( | const Vector3 & | _t | ) | 
Set the translational values [ (0, 3) (1, 3) (2, 3) ].
| [in] | _t | Values to set | 
Perform an affine transformation.
| _v | Vector3 value for the transformation | 
| 
 | friend | 
Stream insertion operator.
| _out | output stream | 
| _m | Matrix to output | 
| 
 | static | 
Identity matrix.
| 
 | protected | 
The 4x4 matrix.
Referenced by operator[]().
| 
 | static | 
Zero matrix.