17 #ifndef _GAZEBO_MATRIX4_HH_    18 #define _GAZEBO_MATRIX4_HH_    22 #include <ignition/math/Matrix4.hh>    51       public: 
Matrix4(
const ignition::math::Matrix4d &_m);
    70       public: 
Matrix4(
double _v00, 
double _v01, 
double _v02, 
double _v03,
    71                       double _v10, 
double _v11, 
double _v12, 
double _v13,
    72                       double _v20, 
double _v21, 
double _v22, 
double _v23,
    73                       double _v30, 
double _v31, 
double _v32, 
double _v33);
    95       public: 
void Set(
double _v00, 
double _v01, 
double _v02, 
double _v03,
    96                        double _v10, 
double _v11, 
double _v12, 
double _v13,
    97                        double _v20, 
double _v21, 
double _v22, 
double _v23,
    98                        double _v30, 
double _v31, 
double _v32, 
double _v33);
   104       public: 
void SetTranslate(
const Vector3 &_t);
   108       public: 
Vector3 GetTranslation() 
const;
   116       public: 
Vector3 GetEulerRotation(
unsigned int solution_number = 1) 
const;
   124       public: 
void SetScale(
const Vector3 &_s);
   128       public: 
bool IsAffine() 
const;
   137       public: 
Matrix4 Inverse() 
const;
   147       public: 
Matrix4 &operator=(
const ignition::math::Matrix4d &_mat);
   176                 return this->m[_row];
   183                 return this->m[_row];
   190       public: 
bool operator==(
const Matrix4 &_m) 
const;
   194       public: ignition::math::Matrix4d Ign() 
const;
   203               for (
int i = 0; i < 4; i++)
   205                 for (
int j = 0; j < 4; j++)
   207                   _out << (fabs(_m.
m[i][j]) < 1e-6 ? 0 : _m.
m[i][j]) << 
" ";
   222       protected: 
double m[4][4];
 
Forward declarations for the common classes. 
Definition: Animation.hh:33
 
Encapsulates a position and rotation in three space. 
Definition: Pose.hh:37
 
The Vector3 class represents the generic vector containing 3 elements. 
Definition: Vector3.hh:39
 
static const Matrix4 IDENTITY
Identity matrix. 
Definition: Matrix4.hh:216
 
A 3x3 matrix class. 
Definition: Matrix4.hh:40
 
double * operator[](size_t _row)
Array subscript operator. 
Definition: Matrix4.hh:173
 
A 3x3 matrix class. 
Definition: Matrix3.hh:34
 
A quaternion class. 
Definition: Quaternion.hh:42
 
GAZEBO_VISIBLE void Set(common::Image &_img, const msgs::Image &_msg)
Convert a msgs::Image to a common::Image. 
 
double m[4][4]
The 4x4 matrix. 
Definition: Matrix4.hh:222
 
static const Matrix4 ZERO
Zero matrix. 
Definition: Matrix4.hh:219
 
const double * operator[](size_t _row) const
Definition: Matrix4.hh:180
 
friend std::ostream & operator<<(std::ostream &_out, const gazebo::math::Matrix4 &_m)
Stream insertion operator. 
Definition: Matrix4.hh:200