Ravelin
Matrix2.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 MATRIX2
8 #error This class is not to be included by the user directly. Use Matrix2d.h or Matrix2f.h instead.
9 #endif
10 
11 class MATRIXN;
12 class SHAREDMATRIXN;
14 
16 class MATRIX2
17 {
18  public:
19  MATRIX2() {}
20  MATRIX2(const REAL* array);
21  MATRIX2(REAL m00, REAL m01, REAL m10, REAL m11);
22  MATRIX2(const MATRIX2& source) { operator=(source); }
23  MATRIX2(const MATRIXN& m) { operator=(m); }
24  MATRIX2(const SHAREDMATRIXN& m) { operator=(m); }
25  MATRIX2(const CONST_SHAREDMATRIXN& m) { operator=(m); }
26  unsigned size() const { return 4; }
27  unsigned rows() const { return 2; }
28  unsigned columns() const { return 2; }
29  bool is_symmetric(REAL tolerance) const;
30  bool orthonormalize();
31  bool is_orthonormal() const;
32  REAL det() const;
34  static MATRIX2 invert(const MATRIX2& m);
35  MATRIX2 inverse() const { MATRIX2 m = *this; return m.invert(); }
36  void set_rot_Z(REAL angle);
37  static MATRIX2 rot_Z(REAL angle);
38  static MATRIX2 transpose(const MATRIX2& m);
39  void transpose();
40  static bool valid_rotation(const MATRIX2& R);
41  static MATRIX2 identity() { MATRIX2 m; m.set_identity(); return m; }
42  static MATRIX2 zero() { MATRIX2 m; m.set_zero(); return m; }
43  ORIGIN2 get_row(unsigned i) const;
44  ORIGIN2 get_column(unsigned i) const;
45  void set_identity();
46  void set_zero();
47  ORIGIN2 mult(const ORIGIN2& v) const;
48  ORIGIN2 transpose_mult(const ORIGIN2& v) const;
49  MATRIX2 mult(const MATRIX2& m) const;
50  MATRIX2 transpose_mult(const MATRIX2& m) const;
52  MATRIX2 mult_transpose(const MATRIX2& m) const;
53  MATRIX2& operator=(const MATRIX2& source);
54  MATRIX2& operator=(const MATRIXN& source);
55  MATRIX2& operator=(const SHAREDMATRIXN& source);
56  MATRIX2& operator=(const CONST_SHAREDMATRIXN& source);
57  MATRIX2& operator+=(const MATRIX2& m);
58  MATRIX2& operator-=(const MATRIX2& m);
59  MATRIX2& operator*=(const MATRIX2& m) { return *this = *this * m; }
60  MATRIX2& operator*=(REAL scalar);
61  MATRIX2& operator/=(REAL scalar) { return operator*=(1.0/scalar); }
62  ORIGIN2 operator*(const ORIGIN2& o) const { return mult(o); }
63  MATRIX2 operator+(const MATRIX2& m) const { MATRIX2 n = *this; n += m; return n; }
64  MATRIX2 operator-(const MATRIX2& m) const { MATRIX2 n = *this; n -= m; return n; }
65  MATRIX2 operator*(const MATRIX2& m) const { return mult(m); }
66  MATRIX2 operator*(REAL scalar) const { MATRIX2 m = *this; m *= scalar; return m; }
67  MATRIX2 operator/(REAL scalar) const { return operator*(1.0/scalar); }
68  MATRIX2 operator-() const;
69  unsigned leading_dim() const { return 2; }
70  unsigned inc() const { return 1; }
71  const REAL& xx() const { return _data[0]; }
72  const REAL& yx() const { return _data[1]; }
73  const REAL& xy() const { return _data[2]; }
74  const REAL& yy() const { return _data[3]; }
75  REAL& xx() { return _data[0]; }
76  REAL& yx() { return _data[1]; }
77  REAL& xy() { return _data[2]; }
78  REAL& yy() { return _data[3]; }
79  REAL& operator()(unsigned i, unsigned j);
80  const REAL& operator()(unsigned i, unsigned j) const;
81  MATRIX2& resize(unsigned rows, unsigned columns, bool preserve = false);
82  const REAL* data(unsigned i) const;
83  REAL* data(unsigned i);
84 
86  const REAL* data() const { return _data; }
87 
89  REAL* data() { return _data; }
90 
91  #define MATRIXX MATRIX2
92  #include "MatrixCommon.inl"
93  #undef MATRIXX
94 
95  private:
96  bool orthonormalize(VECTOR2& a, VECTOR2& b);
97  REAL _data[4];
98 }; // end class
99 
100 std::ostream& operator<<(std::ostream& out, const MATRIX2& m);
101 
MATRIX2 & operator-=(const MATRIX2 &m)
Subtracts m from this in place.
Definition: Matrix2.cpp:382
ORIGIN2 get_column(unsigned i) const
Gets the specified column of the matrix.
Definition: Matrix2.cpp:283
const REAL * data() const
Gets a constant pointer to the beginning of the matrix array.
Definition: Matrix2.h:86
A general 2x2 matrix.
Definition: Matrix2.h:16
ORIGIN2 transpose_mult(const ORIGIN2 &v) const
Multiplies the transpose of this matrix by a vector and returns the result in a new vector...
Definition: Matrix2.cpp:127
void set_zero()
Sets this matrix to zero.
Definition: Matrix2.cpp:396
MATRIX2 mult_transpose(const MATRIX2 &m) const
Multiplies this matrix by the transpose of a matrix and returns the result in a new matrix...
Definition: Matrix2.cpp:160
A two-dimensional floating point vector used for computational geometry calculations and with associa...
Definition: Vector2.h:15
bool is_orthonormal() const
Determines whether this is an orthonormal matrix.
Definition: Matrix2.cpp:195
ORIGIN2 get_row(unsigned i) const
Gets the specified row of the matrix.
Definition: Matrix2.cpp:272
A generic, possibly non-square matrix.
Definition: MatrixN.h:18
void set_identity()
Sets this matrix to identity.
Definition: Matrix2.cpp:389
bool orthonormalize()
Makes the matrix orthonormal using Gram-Schmidt orthogonalization.
Definition: Matrix2.cpp:250
REAL det() const
Calculates the determinant for a 2x2 matrix.
Definition: Matrix2.cpp:189
A generic, possibly non-square matrix using shared data.
Definition: SharedMatrixN.h:59
REAL * data()
Gets a pointer to the beginning of the matrix array.
Definition: Matrix2.h:89
MATRIX2 & invert()
Inverts this matrix.
Definition: Matrix2.cpp:182
MATRIX2 operator-() const
Returns the negation of this matrix.
Definition: Matrix2.cpp:367
static MATRIX2 rot_Z(REAL angle)
Returns the rotation matrix of the specified angle around the Z axis.
Definition: Matrix2.cpp:216
MATRIX2 & operator=(const MATRIX2 &source)
Copies a matrix to this one.
Definition: Matrix2.cpp:306
void transpose()
Sets this matrix to its transpose.
Definition: Matrix2.cpp:291
ORIGIN2 mult(const ORIGIN2 &v) const
Multiplies this matrix by a vector and returns the result in a new vector.
Definition: Matrix2.cpp:116
MATRIX2 transpose_mult_transpose(const MATRIX2 &m) const
Multiplies the transpose of this matrix by the transpose of a matrix and returns the result in a new ...
Definition: Matrix2.cpp:149
A generic, possibly non-square matrix using constant shared data.
Definition: SharedMatrixN.h:19
A two-dimensional floating point vector used for computational geometry calculations and without asso...
Definition: Origin2.h:14
void set_rot_Z(REAL angle)
Sets this matrix to the rotation matrix of the specified angle around the Z axis. ...
Definition: Matrix2.cpp:210
MATRIX2 & operator+=(const MATRIX2 &m)
Adds m to this in place.
Definition: Matrix2.cpp:375
bool is_symmetric(REAL tolerance) const
Checks whether this matrix is symmetric.
Definition: Matrix2.cpp:402