APM:Libraries
quaternion.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 2012 Andrew Tridgell, all rights reserved.
17 // Refactored by Jonathan Challinger
18 #pragma once
19 
20 #include <cmath>
21 #if MATH_CHECK_INDEXES
22 #include <assert.h>
23 #endif
24 
25 class Quaternion {
26 public:
27  float q1, q2, q3, q4;
28 
29  // constructor creates a quaternion equivalent
30  // to roll=0, pitch=0, yaw=0
32  {
33  q1 = 1;
34  q2 = q3 = q4 = 0;
35  }
36 
37  // setting constructor
38  Quaternion(const float _q1, const float _q2, const float _q3, const float _q4) :
39  q1(_q1), q2(_q2), q3(_q3), q4(_q4)
40  {
41  }
42 
43  // setting constructor
44  Quaternion(const float _q[4]) :
45  q1(_q[0]), q2(_q[1]), q3(_q[2]), q4(_q[3])
46  {
47  }
48 
49  // function call operator
50  void operator()(const float _q1, const float _q2, const float _q3, const float _q4)
51  {
52  q1 = _q1;
53  q2 = _q2;
54  q3 = _q3;
55  q4 = _q4;
56  }
57 
58  // check if any elements are NAN
59  bool is_nan(void) const
60  {
61  return isnan(q1) || isnan(q2) || isnan(q3) || isnan(q4);
62  }
63 
64  // return the rotation matrix equivalent for this quaternion
65  void rotation_matrix(Matrix3f &m) const;
66 
67  // return the rotation matrix equivalent for this quaternion after normalization
68  void rotation_matrix_norm(Matrix3f &m) const;
69 
70  void from_rotation_matrix(const Matrix3f &m);
71 
72  // convert a vector from earth to body frame
73  void earth_to_body(Vector3f &v) const;
74 
75  // create a quaternion from Euler angles
76  void from_euler(float roll, float pitch, float yaw);
77 
78  void from_vector312(float roll ,float pitch, float yaw);
79 
80  void to_axis_angle(Vector3f &v);
81 
82  void from_axis_angle(Vector3f v);
83 
84  void from_axis_angle(const Vector3f &axis, float theta);
85 
86  void rotate(const Vector3f &v);
87 
89 
90  void from_axis_angle_fast(const Vector3f &axis, float theta);
91 
92  void rotate_fast(const Vector3f &v);
93 
94  // get euler roll angle
95  float get_euler_roll() const;
96 
97  // get euler pitch angle
98  float get_euler_pitch() const;
99 
100  // get euler yaw angle
101  float get_euler_yaw() const;
102 
103  // create eulers from a quaternion
104  void to_euler(float &roll, float &pitch, float &yaw) const;
105 
106  // create eulers from a quaternion
107  Vector3f to_vector312(void) const;
108 
109  float length(void) const;
110  void normalize();
111 
112  // initialise the quaternion to no rotation
113  void initialise()
114  {
115  q1 = 1.0f;
116  q2 = q3 = q4 = 0.0f;
117  }
118 
119  Quaternion inverse(void) const;
120 
121  // allow a quaternion to be used as an array, 0 indexed
122  float & operator[](uint8_t i)
123  {
124  float *_v = &q1;
125 #if MATH_CHECK_INDEXES
126  assert(i < 4);
127 #endif
128  return _v[i];
129  }
130 
131  const float & operator[](uint8_t i) const
132  {
133  const float *_v = &q1;
134 #if MATH_CHECK_INDEXES
135  assert(i < 4);
136 #endif
137  return _v[i];
138  }
139 
140  Quaternion operator*(const Quaternion &v) const;
141  Quaternion &operator*=(const Quaternion &v);
142  Quaternion operator/(const Quaternion &v) const;
143 };
void to_euler(float &roll, float &pitch, float &yaw) const
Definition: quaternion.cpp:272
Quaternion(const float _q[4])
Definition: quaternion.h:44
Quaternion operator/(const Quaternion &v) const
Definition: quaternion.cpp:350
float get_euler_yaw() const
Definition: quaternion.cpp:266
void to_axis_angle(Vector3f &v)
Definition: quaternion.cpp:189
void from_vector312(float roll, float pitch, float yaw)
Definition: quaternion.cpp:146
float q1
Definition: quaternion.h:27
Quaternion(const float _q1, const float _q2, const float _q3, const float _q4)
Definition: quaternion.h:38
void from_euler(float roll, float pitch, float yaw)
Definition: quaternion.cpp:130
Quaternion & operator*=(const Quaternion &v)
Definition: quaternion.cpp:330
const float & operator[](uint8_t i) const
Definition: quaternion.h:131
Quaternion operator*(const Quaternion &v) const
Definition: quaternion.cpp:309
void from_rotation_matrix(const Matrix3f &m)
Definition: quaternion.cpp:76
float q3
Definition: quaternion.h:27
void initialise()
Definition: quaternion.h:113
float get_euler_roll() const
Definition: quaternion.cpp:254
float get_euler_pitch() const
Definition: quaternion.cpp:260
void rotation_matrix(Matrix3f &m) const
Definition: quaternion.cpp:24
float v
Definition: Printf.cpp:15
void from_axis_angle(Vector3f v)
Definition: quaternion.cpp:154
void operator()(const float _q1, const float _q2, const float _q3, const float _q4)
Definition: quaternion.h:50
void from_axis_angle_fast(Vector3f v)
Definition: quaternion.cpp:199
void normalize()
Definition: quaternion.cpp:297
Vector3f to_vector312(void) const
Definition: quaternion.cpp:280
float & operator[](uint8_t i)
Definition: quaternion.h:122
float q4
Definition: quaternion.h:27
Quaternion inverse(void) const
Definition: quaternion.cpp:292
void rotate(const Vector3f &v)
Definition: quaternion.cpp:182
bool is_nan(void) const
Definition: quaternion.h:59
float length(void) const
Definition: quaternion.cpp:287
void earth_to_body(Vector3f &v) const
Definition: quaternion.cpp:122
float q2
Definition: quaternion.h:27
void rotation_matrix_norm(Matrix3f &m) const
Definition: quaternion.cpp:48
void rotate_fast(const Vector3f &v)
Definition: quaternion.cpp:223