Ravelin
Matrix3.h
1 /****************************************************************************
2  * Copyright 2013 Evan Drumwright
3  * This library is distributed under the terms of the Apache V2.0
4  * License (obtainable from http://www.apache.org/licenses/LICENSE-2.0).
5  ****************************************************************************/
6 
7 #ifndef MATRIX3
8 #error This class is not to be included by the user directly. Use Matrix3d.h or Matrix3f.h instead.
9 #endif
10 
11 class QUAT;
12 class AANGLE;
13 class MATRIXN;
14 class SHAREDMATRIXN;
18 
20 class MATRIX3
21 {
22  public:
23  MATRIX3() { }
24  MATRIX3(const MATRIX3& source) { operator=(source); }
25  MATRIX3(const REAL* array);
26  MATRIX3(const QUAT& q) { operator=(q); }
27  MATRIX3(const AANGLE& a) { operator=(a); }
28  MATRIX3(REAL, REAL, REAL, REAL, REAL, REAL, REAL, REAL, REAL);
29  MATRIX3& operator=(const QUAT& q);
30  MATRIX3& operator=(const AANGLE& a);
31  MATRIX3(const MATRIXN& m) { operator=(m); }
32  MATRIX3(const SHAREDMATRIXN& m) { operator=(m); }
33  MATRIX3(const CONST_SHAREDMATRIXN& m) { operator=(m); }
34  REAL norm_inf() const;
35  unsigned rows() const { return 3; }
36  unsigned columns() const { return 3; }
37  bool is_symmetric(REAL tolerance) const;
38  bool orthonormalize();
39  bool is_orthonormal() const;
40  REAL det() const;
41  MATRIX3& invert();
42  const REAL& xx() const { return _data[0]; }
43  REAL& xx() { return _data[0]; }
44  const REAL& xy() const { return _data[3]; }
45  REAL& xy() { return _data[3]; }
46  const REAL& xz() const { return _data[6]; }
47  REAL& xz() { return _data[6]; }
48  const REAL& yx() const { return _data[1]; }
49  REAL& yx() { return _data[1]; }
50  const REAL& yy() const { return _data[4]; }
51  REAL& yy() { return _data[4]; }
52  const REAL& yz() const { return _data[7]; }
53  REAL& yz() { return _data[7]; }
54  const REAL& zx() const { return _data[2]; }
55  REAL& zx() { return _data[2]; }
56  const REAL& zy() const { return _data[5]; }
57  REAL& zy() { return _data[5]; }
58  const REAL& zz() const { return _data[8]; }
59  REAL& zz() { return _data[8]; }
60  static VECTOR3 calc_differential(const MATRIX3& R1, const MATRIX3& R2);
61  static MATRIX3 invert(const MATRIX3& m);
62  MATRIX3 inverse() const { MATRIX3 m = *this; return m.invert(); }
63  void set_rot_X(REAL angle);
64  static MATRIX3 rot_X(REAL angle);
65  void set_rot_Y(REAL angle);
66  static MATRIX3 rot_Y(REAL angle);
67  void set_rot_Z(REAL angle);
68  static MATRIX3 rot_Z(REAL angle);
69  static MATRIX3 skew_symmetric(REAL a, REAL b, REAL c);
70  static MATRIX3 skew_symmetric(const ORIGIN3& o);
71  static MATRIX3 skew_symmetric(const VECTOR3& v);
72  static VECTOR3 inverse_skew_symmetric(const MATRIX3& R);
73  static MATRIX3 transpose(const MATRIX3& m);
74  void transpose();
75  static bool valid_rotation(const MATRIX3& R);
76  static bool valid_rotation_scale(const MATRIX3& R);
77  static MATRIX3 identity() { MATRIX3 m; m.set_identity(); return m; }
78  MATRIX3& set_zero(unsigned m, unsigned n) { resize(m,n); set_zero(); return *this; }
79  static MATRIX3 zero() { MATRIX3 m; m.set_zero(); return m; }
81  MATRIX3& set_zero() { std::fill_n(_data, 9, (REAL) 0.0); return *this; }
82  ORIGIN3 transpose_mult(const ORIGIN3& v) const;
83  ORIGIN3 mult(const ORIGIN3& v) const;
84  MATRIX3 mult(const MATRIX3& m) const;
85  MATRIX3 transpose_mult(const MATRIX3& m) const;
86  MATRIX3 mult_transpose(const MATRIX3& m) const;
88  MATRIX3& operator=(const MATRIX3& source);
89  MATRIX3& operator=(const MATRIXN& source);
90  MATRIX3& operator=(const SHAREDMATRIXN& source);
91  MATRIX3& operator=(const CONST_SHAREDMATRIXN& source);
92  MATRIX3& operator+=(const MATRIX3& m);
93  MATRIX3& operator-=(const MATRIX3& m);
94  MATRIX3& operator*=(REAL scalar);
95  MATRIX3& operator/=(REAL scalar) { return operator*=(1.0/scalar); }
96  MATRIX3 operator+(const MATRIX3& m) const { MATRIX3 n = *this; n += m; return n; }
97  MATRIX3 operator-(const MATRIX3& m) const { MATRIX3 n = *this; n -= m; return n; }
98  MATRIX3 operator*(REAL scalar) const { MATRIX3 m = *this; m *= scalar; return m; }
99  MATRIX3 operator/(REAL scalar) const { return operator*(1.0/scalar); }
100  MATRIX3 operator-() const;
101  MATRIX3 operator*(const MATRIX3& m) const { MATRIX3 result; mult(m, result); return result; }
102  ORIGIN3 operator*(const ORIGIN3& v) const { ORIGIN3 result; mult(v, result); return result; }
103  unsigned leading_dim() const { return 3; }
104  unsigned inc() const { return 1; }
105  ORIGIN3 get_column(unsigned i) const;
106  ORIGIN3 get_row(unsigned i) const;
107  REAL& operator()(unsigned i, unsigned j);
108  const REAL& operator()(unsigned i, unsigned j) const;
109  MATRIX3& resize(unsigned rows, unsigned columns, bool preserve = false);
110  const REAL* data(unsigned i) const;
111  REAL* data(unsigned i);
112 
114  unsigned size() const { return 9; }
115 
117  const REAL* data() const { return _data; }
118 
120  REAL* data() { return _data; }
121 
122  #define MATRIXX MATRIX3
123  #include "MatrixCommon.inl"
124  #undef MATRIXX
125 
126  private:
127  bool orthonormalize(VECTOR3& a, VECTOR3& b, VECTOR3& c);
128  REAL _data[9];
129 }; // end class
130 
131 std::ostream& operator<<(std::ostream& out, const MATRIX3& m);
132 
static MATRIX3 rot_Y(REAL angle)
Returns the rotation matrix of the specified angle around the Y axis.
Definition: Matrix3.cpp:361
Quaternion class used for orientation.
Definition: Quat.h:21
ORIGIN3 mult(const ORIGIN3 &v) const
Multiplies this matrix by a vector and returns the result in a new vector.
Definition: Matrix3.cpp:151
void set_rot_Z(REAL angle)
Sets this matrix to the rotation matrix of the specified angle around the Z axis. ...
Definition: Matrix3.cpp:379
bool orthonormalize()
Makes the matrix orthonormal using Gram-Schmidt orthogonalization.
Definition: Matrix3.cpp:472
MATRIX3 mult_transpose(const MATRIX3 &m) const
Multiplies this matrix by a transposed matrix and returns the result in a new matrix.
Definition: Matrix3.cpp:184
ORIGIN3 transpose_mult(const ORIGIN3 &v) const
Multiplies the transpose of this matrix by a vector and returns the result in a new vector...
Definition: Matrix3.cpp:118
static MATRIX3 rot_X(REAL angle)
Returns the rotation matrix of the specified angle around the X axis.
Definition: Matrix3.cpp:337
static VECTOR3 calc_differential(const MATRIX3 &R1, const MATRIX3 &R2)
Calculates the differential between two rotations.
Definition: Matrix3.cpp:644
A generic, possibly non-square matrix.
Definition: MatrixN.h:18
ORIGIN3 get_row(unsigned i) const
Gets the specified row of the matrix.
Definition: Matrix3.cpp:503
A generic N-dimensional floating point vector.
Definition: SharedVectorN.h:77
bool is_symmetric(REAL tolerance) const
Checks whether this matrix is symmetric.
Definition: Matrix3.cpp:629
REAL norm_inf() const
Computes the l-infinity norm of this matrix.
Definition: Matrix3.cpp:230
Class for representation of orientation by an angle around an axis.
Definition: AAngle.h:15
A generic, possibly non-square matrix using shared data.
Definition: SharedMatrixN.h:59
MATRIX3 operator-() const
Returns the negation of this matrix.
Definition: Matrix3.cpp:598
ORIGIN3 get_column(unsigned i) const
Gets the specified column of the matrix.
Definition: Matrix3.cpp:514
MATRIX3 transpose_mult_transpose(const MATRIX3 &m) const
Multiplies the transpose of this matrix by a transposed matrix and returns the result in a new matrix...
Definition: Matrix3.cpp:207
A generic N-dimensional floating point vector.
Definition: SharedVectorN.h:15
static MATRIX3 rot_Z(REAL angle)
Returns the rotation matrix of the specified angle around the Z axis.
Definition: Matrix3.cpp:385
const REAL * data() const
Gets constant pointer to the beginning of the matrix array.
Definition: Matrix3.h:117
MATRIX3 & operator*=(REAL scalar)
Multiplies this matrix by a scalar in place.
Definition: Matrix3.cpp:590
void set_rot_Y(REAL angle)
Sets this matrix to the rotation matrix of the specified angle around the Y axis. ...
Definition: Matrix3.cpp:355
static bool valid_rotation_scale(const MATRIX3 &R)
Checks whether this matrix represents a valid rotation and scale for a right-handed coordinate system...
Definition: Matrix3.cpp:403
static VECTOR3 inverse_skew_symmetric(const MATRIX3 &R)
Constructs the vector from a skew-symmetric matrix.
Definition: Matrix3.cpp:242
MATRIX3 & operator-=(const MATRIX3 &m)
Subtracts m from this in place.
Definition: Matrix3.cpp:613
A three-dimensional floating point vector used for representing points and vectors in 3D with associa...
Definition: Vector3.h:15
A three-dimensional floating point vector used for representing points and vectors in 3D and without ...
Definition: Origin3.h:16
void transpose()
Sets this matrix to its transpose.
Definition: Matrix3.cpp:522
static bool valid_rotation(const MATRIX3 &R)
Checks whether this matrix represents a valid rotation for a right-handed coordinate system...
Definition: Matrix3.cpp:426
static MATRIX3 skew_symmetric(REAL a, REAL b, REAL c)
Constructs a skew-symmetric matrix from the given values.
Definition: Matrix3.cpp:260
A generic, possibly non-square matrix using constant shared data.
Definition: SharedMatrixN.h:19
REAL det() const
Calculates the determinant for a 3x3 matrix.
Definition: Matrix3.cpp:297
REAL * data()
Gets pointer to the beginning of the matrix array.
Definition: Matrix3.h:120
MATRIX3 & invert()
Inverts this matrix.
Definition: Matrix3.cpp:290
unsigned size() const
Gets the total number of elements in this matrix.
Definition: Matrix3.h:114
MATRIX3 & operator+=(const MATRIX3 &m)
Adds m to this in place.
Definition: Matrix3.cpp:606
void set_rot_X(REAL angle)
Sets this matrix to the rotation matrix of the specified angle around the X axis. ...
Definition: Matrix3.cpp:331
A 3x3 matrix that may be used for orientation, inertia tensors, etc.
Definition: Matrix3.h:20
bool is_orthonormal() const
Determines whether this is an orthonormal matrix.
Definition: Matrix3.cpp:307
MATRIX3 & set_identity()
Sets this matrix to identity.
Definition: Matrix3.cpp:620