APM:Libraries
matrix3.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 // Copyright 2010 Michael Smith, all rights reserved.
17 
18 // Inspired by:
19 /****************************************
20  * 3D Vector Classes
21  * By Bill Perone (billperone@yahoo.com)
22  */
23 
24 //
25 // 3x3 matrix implementation.
26 //
27 // Note that the matrix is organised in row-normal form (the same as
28 // applies to array indexing).
29 //
30 // In addition to the template, this header defines the following types:
31 //
32 // Matrix3i 3x3 matrix of signed integers
33 // Matrix3ui 3x3 matrix of unsigned integers
34 // Matrix3l 3x3 matrix of signed longs
35 // Matrix3ul 3x3 matrix of unsigned longs
36 // Matrix3f 3x3 matrix of signed floats
37 //
38 #pragma once
39 
40 #include "vector3.h"
41 
42 // 3x3 matrix with elements of type T
43 template <typename T>
44 class Matrix3 {
45 public:
46 
47  // Vectors comprising the rows of the matrix
49 
50  // trivial ctor
51  // note that the Vector3 ctor will zero the vector elements
53 
54  // setting ctor
55  constexpr Matrix3<T>(const Vector3<T> &a0, const Vector3<T> &b0, const Vector3<T> &c0)
56  : a(a0)
57  , b(b0)
58  , c(c0) {}
59 
60  // setting ctor
61  constexpr Matrix3<T>(const T ax, const T ay, const T az,
62  const T bx, const T by, const T bz,
63  const T cx, const T cy, const T cz)
64  : a(ax,ay,az)
65  , b(bx,by,bz)
66  , c(cx,cy,cz) {}
67 
68  // function call operator
69  void operator () (const Vector3<T> &a0, const Vector3<T> &b0, const Vector3<T> &c0)
70  {
71  a = a0; b = b0; c = c0;
72  }
73 
74  // test for equality
75  bool operator == (const Matrix3<T> &m)
76  {
77  return (a==m.a && b==m.b && c==m.c);
78  }
79 
80  // test for inequality
81  bool operator != (const Matrix3<T> &m)
82  {
83  return (a!=m.a || b!=m.b || c!=m.c);
84  }
85 
86  // negation
87  Matrix3<T> operator - (void) const
88  {
89  return Matrix3<T>(-a,-b,-c);
90  }
91 
92  // addition
94  {
95  return Matrix3<T>(a+m.a, b+m.b, c+m.c);
96  }
98  {
99  return *this = *this + m;
100  }
101 
102  // subtraction
104  {
105  return Matrix3<T>(a-m.a, b-m.b, c-m.c);
106  }
108  {
109  return *this = *this - m;
110  }
111 
112  // uniform scaling
113  Matrix3<T> operator * (const T num) const
114  {
115  return Matrix3<T>(a*num, b*num, c*num);
116  }
118  {
119  return *this = *this * num;
120  }
121  Matrix3<T> operator / (const T num) const
122  {
123  return Matrix3<T>(a/num, b/num, c/num);
124  }
126  {
127  return *this = *this / num;
128  }
129 
130  // allow a Matrix3 to be used as an array of vectors, 0 indexed
131  Vector3<T> & operator[](uint8_t i) {
132  Vector3<T> *_v = &a;
133 #if MATH_CHECK_INDEXES
134  assert(i >= 0 && i < 3);
135 #endif
136  return _v[i];
137  }
138 
139  const Vector3<T> & operator[](uint8_t i) const {
140  const Vector3<T> *_v = &a;
141 #if MATH_CHECK_INDEXES
142  assert(i >= 0 && i < 3);
143 #endif
144  return _v[i];
145  }
146 
147  // multiplication by a vector
148  Vector3<T> operator *(const Vector3<T> &v) const;
149 
150  // multiplication of transpose by a vector
151  Vector3<T> mul_transpose(const Vector3<T> &v) const;
152 
153  // multiplication by a vector giving a Vector2 result (XY components)
154  Vector2<T> mulXY(const Vector3<T> &v) const;
155 
156  // extract x column
157  Vector3<T> colx(void) const
158  {
159  return Vector3<T>(a.x, b.x, c.x);
160  }
161 
162  // extract y column
163  Vector3<T> coly(void) const
164  {
165  return Vector3<T>(a.y, b.y, c.y);
166  }
167 
168  // extract z column
169  Vector3<T> colz(void) const
170  {
171  return Vector3<T>(a.z, b.z, c.z);
172  }
173 
174  // multiplication by another Matrix3<T>
175  Matrix3<T> operator *(const Matrix3<T> &m) const;
176 
178  {
179  return *this = *this * m;
180  }
181 
182  // transpose the matrix
183  Matrix3<T> transposed(void) const;
184 
185  void transpose(void)
186  {
187  *this = transposed();
188  }
189 
195  T det() const;
196 
205  bool inverse(Matrix3<T>& inv) const;
206 
213  bool invert();
214 
215  // zero the matrix
216  void zero(void);
217 
218  // setup the identity matrix
219  void identity(void) {
220  a.x = b.y = c.z = 1;
221  a.y = a.z = 0;
222  b.x = b.z = 0;
223  c.x = c.y = 0;
224  }
225 
226  // check if any elements are NAN
227  bool is_nan(void)
228  {
229  return a.is_nan() || b.is_nan() || c.is_nan();
230  }
231 
232  // create a rotation matrix from Euler angles
233  void from_euler(float roll, float pitch, float yaw);
234 
235  // create eulers from a rotation matrix
236  void to_euler(float *roll, float *pitch, float *yaw) const;
237 
238  // create matrix from rotation enum
239  void from_rotation(enum Rotation rotation);
240 
241  /*
242  calculate Euler angles (312 convention) for the matrix.
243  See http://www.atacolorado.com/eulersequences.doc
244  vector is returned in r, p, y order
245  */
246  Vector3<T> to_euler312() const;
247 
248  /*
249  fill the matrix from Euler angles in radians in 312 convention
250  */
251  void from_euler312(float roll, float pitch, float yaw);
252 
253  // apply an additional rotation from a body frame gyro vector
254  // to a rotation matrix.
255  void rotate(const Vector3<T> &g);
256 
257  // create rotation matrix for rotation about the vector v by angle theta
258  // See: https://en.wikipedia.org/wiki/Rotation_matrix#General_rotations
259  // "Rotation matrix from axis and angle"
260  void from_axis_angle(const Vector3<T> &v, float theta);
261 
262  // normalize a rotation matrix
263  void normalize(void);
264 };
265 
void to_euler(float *roll, float *pitch, float *yaw) const
Definition: matrix3.cpp:49
Matrix3< T > & operator*=(const T num)
Definition: matrix3.h:117
Matrix3< T > & operator/=(const T num)
Definition: matrix3.h:125
bool operator==(const Matrix3< T > &m)
Definition: matrix3.h:75
Matrix3< uint32_t > Matrix3ul
Definition: matrix3.h:269
Matrix3< T > operator/(const T num) const
Definition: matrix3.h:121
Vector2< T > mulXY(const Vector3< T > &v) const
Definition: matrix3.cpp:157
void from_axis_angle(const Vector3< T > &v, float theta)
Definition: matrix3.cpp:248
Matrix3< double > Matrix3d
Definition: matrix3.h:271
bool is_nan(void) const
Definition: vector3.cpp:315
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
Matrix3< float > Matrix3f
Definition: matrix3.h:270
void operator()(const Vector3< T > &a0, const Vector3< T > &b0, const Vector3< T > &c0)
Definition: matrix3.h:69
Rotation
Definition: rotations.h:27
Vector3< T > & operator[](uint8_t i)
Definition: matrix3.h:131
Vector3< T > colz(void) const
Definition: matrix3.h:169
Matrix3< T > transposed(void) const
Definition: matrix3.cpp:189
Matrix3< int16_t > Matrix3i
Definition: matrix3.h:266
Matrix3< T > operator+(const Matrix3< T > &m) const
Definition: matrix3.h:93
#define constexpr
Definition: AP_HAL_Macros.h:16
Vector3< T > coly(void) const
Definition: matrix3.h:163
T y
Definition: vector3.h:67
Vector3< T > c
Definition: matrix3.h:48
Matrix3< T > operator-(void) const
Definition: matrix3.h:87
Vector3< T > to_euler312() const
Definition: matrix3.cpp:81
T z
Definition: vector3.h:67
void from_rotation(enum Rotation rotation)
Definition: matrix3.cpp:63
Matrix3< T > & operator-=(const Matrix3< T > &m)
Definition: matrix3.h:107
bool is_nan(void)
Definition: matrix3.h:227
Matrix3< T > operator*(const T num) const
Definition: matrix3.h:113
float v
Definition: Printf.cpp:15
const Vector3< T > & operator[](uint8_t i) const
Definition: matrix3.h:139
Vector3< T > mul_transpose(const Vector3< T > &v) const
Definition: matrix3.cpp:165
void zero(void)
Definition: matrix3.cpp:238
void from_euler312(float roll, float pitch, float yaw)
Definition: matrix3.cpp:92
bool invert()
Definition: matrix3.cpp:227
void transpose(void)
Definition: matrix3.h:185
Matrix3< T > & operator+=(const Matrix3< T > &m)
Definition: matrix3.h:97
T det() const
Definition: matrix3.cpp:197
bool inverse(Matrix3< T > &inv) const
Definition: matrix3.cpp:205
Vector3< T > b
Definition: matrix3.h:48
void rotate(const Vector3< T > &g)
Definition: matrix3.cpp:115
bool operator!=(const Matrix3< T > &m)
Definition: matrix3.h:81
void normalize(void)
Definition: matrix3.cpp:135
void uint32_t num
Definition: systick.h:80
Vector3< T > a
Definition: matrix3.h:48
Matrix3< int32_t > Matrix3l
Definition: matrix3.h:268
void identity(void)
Definition: matrix3.h:219
Vector3< T > colx(void) const
Definition: matrix3.h:157
T x
Definition: vector3.h:67
Matrix3< uint16_t > Matrix3ui
Definition: matrix3.h:267