SF2 C++ FRC Class Library
Sensor Fusion Framework (SF2) for FRC
Quaternion.h
1 /* ============================================
2  SF2 source code is placed under the MIT license
3  Copyright (c) 2017 Kauai Labs
4 
5  Permission is hereby granted, free of charge, to any person obtaining a copy
6  of this software and associated documentation files (the "Software"), to deal
7  in the Software without restriction, including without limitation the rights
8  to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9  copies of the Software, and to permit persons to whom the Software is
10  furnished to do so, subject to the following conditions:
11 
12  The above copyright notice and this permission notice shall be included in
13  all copies or substantial portions of the Software.
14 
15  THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16  IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17  FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18  AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19  LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20  OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
21  THE SOFTWARE.
22  ===============================================
23  */
24 
25 #ifndef SRC_ORIENTATION_QUATERNION_H_
26 #define SRC_ORIENTATION_QUATERNION_H_
27 
28 /*----------------------------------------------------------------------------*/
29 /* Copyright (c) Kauai Labs 2016. All Rights Reserved. */
30 /* */
31 /* Created in support of Team 2465 (Kauaibots). Go Purple Wave! */
32 /* */
33 /* Open Source Software - may be modified and shared by FRC teams. Any */
34 /* modifications to this code must be accompanied by the \License.txt file */
35 /* in the root directory of the project. */
36 /*----------------------------------------------------------------------------*/
37 
38 #include <forward_list>
39 #include <vector>
40 using namespace std;
41 
42 #include <math.h>
43 #include "unit/Unit.h"
44 #include "quantity/Scalar.h"
45 
76 class Quaternion: public IInterpolate<Quaternion>, public ICopy<Quaternion>, public IQuantity {
77 
78  float w;
79  float x;
80  float y;
81  float z;
82 
83  class FloatVectorStruct {
84  public:
85  float x;
86  float y;
87  float z;
88  };
89 
90  static Unitless component_units;
91 
92 public:
98  set(1, 0, 0, 0);
99  }
100 
106  Quaternion(const Quaternion& src) {
107  set(src);
108  }
109 
117  Quaternion(float w, float x, float y, float z) {
118  set(w, x, y, z);
119  }
120 
121  ~Quaternion() {
122  }
123 
131  void set(float w, float x, float y, float z) {
132  this->w = w;
133  this->x = x;
134  this->y = y;
135  this->z = z;
136  }
137 
142  void set(const Quaternion& src) {
143  set(src.w, src.x, src.y, src.z);
144  }
145 
151  static void getGravity(FloatVectorStruct& v, const Quaternion& q) {
152  v.x = 2 * ((q.x * q.z) - (q.w * q.y));
153  v.y = 2 * ((q.w * q.x) + (q.y * q.z));
154  v.z = (q.w * q.w) - (q.x * q.x) - (q.y * q.y) + (q.z * q.z);
155  }
156 
165  static void getYawPitchRoll(const Quaternion& q,
166  const FloatVectorStruct& gravity, FloatVectorStruct& ypr) {
167  // yaw: (clockwise rotation, about Z axis)
168  ypr.x = (float) atan2((2 * (q.x * q.y)) - (2 * (q.w * q.z)),
169  (2 * (q.w * q.w)) + (2 * (q.x * q.x)) - 1);
170  // pitch: (tilt up/down, about X axis)
171  ypr.y = (float) atan(
172  gravity.y
173  / sqrt(
174  (gravity.x * gravity.x)
175  + (gravity.z * gravity.z)));
176  // roll: (tilt left/right, about Y axis)
177  ypr.z = (float) atan(
178  gravity.x
179  / sqrt(
180  (gravity.y * gravity.y)
181  + (gravity.z * gravity.z)));
182  }
183 
188  void getYawPitchRollRadians(FloatVectorStruct& ypr) {
189  FloatVectorStruct gravity;
190  getGravity(gravity, *this);
191  getYawPitchRoll(*this, gravity, ypr);
192  }
193 
198  void getYawRadians(Scalar& yaw) {
199  FloatVectorStruct ypr;
200  getYawPitchRollRadians(ypr);
201  yaw.set(ypr.x);
202  }
203 
208  void getPitch(Scalar& pitch) {
209  FloatVectorStruct ypr;
210  getYawPitchRollRadians(ypr);
211  pitch.set(ypr.y);
212  }
213 
218  void getRoll(Scalar& roll) {
219  FloatVectorStruct ypr;
220  getYawPitchRollRadians(ypr);
221  roll.set(ypr.z);
222  }
223 
237  static void slerp(const Quaternion& qa, const Quaternion& qb, double t,
238  Quaternion& out) {
239  // Calculate angle between them.
240  double cosHalfTheta = qa.w * qb.w + qa.x * qb.x + qa.y * qb.y
241  + qa.z * qb.z;
242  // if qa=qb or qa=-qb then theta = 0 and we can return qa
243  if (fabs(cosHalfTheta) >= 1.0) {
244  out.w = qa.w;
245  out.x = qa.x;
246  out.y = qa.y;
247  out.z = qa.z;
248  return;
249  }
250  // Calculate temporary values.
251  double halfTheta = acos(cosHalfTheta);
252  double sinHalfTheta = sqrt(1.0 - cosHalfTheta * cosHalfTheta);
253  // if theta = 180 degrees then result is not fully defined
254  // we could rotate around any axis normal to qa or qb
255  if (fabs(sinHalfTheta) < 0.001) {
256  out.w = (qa.w * 0.5f + qb.w * 0.5f);
257  out.x = (qa.x * 0.5f + qb.x * 0.5f);
258  out.y = (qa.y * 0.5f + qb.y * 0.5f);
259  out.z = (qa.z * 0.5f + qb.z * 0.5f);
260  return;
261  }
262  float ratioA = (float) (sin((1 - t) * halfTheta) / sinHalfTheta);
263  float ratioB = (float) (sin(t * halfTheta) / sinHalfTheta);
264  //calculate Quaternion.
265  out.w = (qa.w * ratioA + qb.w * ratioB);
266  out.x = (qa.x * ratioA + qb.x * ratioB);
267  out.y = (qa.y * ratioA + qb.y * ratioB);
268  out.z = (qa.z * ratioA + qb.z * ratioB);
269  return;
270  }
271 
279  void conjugate() {
280  this->x = -this->x;
281  this->y = -this->y;
282  this->z = -this->z;
283  }
284 
291  void inverse() {
292  this->conjugate();
293  this->divide(dotProduct(*this, *this));
294  }
295 
308  void multiply(const Quaternion& q) {
309  float w, x, y, z;
310 
311  x = this->w * q.x + this->x * q.w + this->y * q.z - this->z * q.y;
312  y = this->w * q.y + this->y * q.w + this->z * q.x - this->x * q.z;
313  z = this->w * q.z + this->z * q.w + this->x * q.y - this->y * q.x;
314  w = this->w * q.w - this->x * q.x - this->y * q.y - this->z * q.z;
315 
316  this->w = w;
317  this->x = x;
318  this->y = y;
319  this->z = z;
320  }
321 
326  void divide(float s) {
327  this->w = this->w / s;
328  this->x = this->x / s;
329  this->y = this->y / s;
330  this->z = this->z / s;
331  }
332 
333  float dotProduct(const Quaternion& q1, const Quaternion& q2) {
334  return q1.x * q2.x + q1.y * q2.y + q1.z * q2.z + q1.w * q2.w;
335  }
336 
351  static void difference(const Quaternion& qa, const Quaternion& qb,
352  Quaternion& q_diff) {
353  q_diff.set(qa.w, qa.x, qa.y, qa.z);
354  q_diff.inverse();
355  q_diff.multiply(qb);
356  }
357 
362  float getW() {
363  return w;
364  }
365 
370  float getX() {
371  return x;
372  }
373 
378  float getY() {
379  return y;
380  }
381 
386  float getZ() {
387  return z;
388  }
389 
390  void interpolate(const Quaternion& to, double time_ratio, Quaternion& out) {
391  Quaternion::slerp(*this, to, time_ratio, out);
392  }
393 
394  void copy(Quaternion& t) {
395  this->w = t.w;
396  this->x = t.x;
397  this->y = t.y;
398  this->z = t.z;
399  }
400 
401  Quaternion* instantiate_copy() {
402  return new Quaternion(*this);
403  }
404 
405  static void getUnits(vector<IUnit *>& units) {
406  units.clear();
407  units.push_back(&Quaternion::component_units);
408  units.push_back(&Quaternion::component_units);
409  units.push_back(&Quaternion::component_units);
410  units.push_back(&Quaternion::component_units);
411  }
412 
413  bool getPrintableString(vector<string>& printable_string) {
414  return false;
415  }
416 
417  bool getContainedQuantities(vector<IQuantity *>& quantities) {
418  quantities.push_back(new Scalar(w));
419  quantities.push_back(new Scalar(x));
420  quantities.push_back(new Scalar(y));
421  quantities.push_back(new Scalar(z));
422  return true;
423  }
424 
425  bool getContainedQuantityNames(vector<string>& quantity_names) {
426  quantity_names.push_back("W");
427  quantity_names.push_back("X");
428  quantity_names.push_back("Y");
429  quantity_names.push_back("Z");
430  return true;
431  }
432 };
433 
434 #endif /* SRC_ORIENTATION_QUATERNION_H_ */
Quaternion(float w, float x, float y, float z)
Constructs a Quaternion instance, using the provides w, x, y and z valuese.
Definition: Quaternion.h:117
static void getGravity(FloatVectorStruct &v, const Quaternion &q)
Extracts the gravity vector from the Quaternion.
Definition: Quaternion.h:151
Definition: ICopy.h:29
The Quaternion class provides methods to operate on a quaternion.
Definition: Quaternion.h:76
static void getYawPitchRoll(const Quaternion &q, const FloatVectorStruct &gravity, FloatVectorStruct &ypr)
Extracts the yaw, pitch and roll values from the Quaternion.
Definition: Quaternion.h:165
float getX()
Accessor for the Quaternion&#39;s X component value.
Definition: Quaternion.h:370
void getYawPitchRollRadians(FloatVectorStruct &ypr)
Extracts the yaw, pitch and roll values from the Quaternion.
Definition: Quaternion.h:188
float getY()
Accessor for the Quaternion&#39;s Y component value.
Definition: Quaternion.h:378
void multiply(const Quaternion &q)
Modifies this quaternion (the multiplicand) to be the product of multiplication by a multiplier Quate...
Definition: Quaternion.h:308
Quaternion(const Quaternion &src)
Constructs a Quaternion instance, using values from another Quaternion instance.
Definition: Quaternion.h:106
static void difference(const Quaternion &qa, const Quaternion &qb, Quaternion &q_diff)
Divides two quaternions.
Definition: Quaternion.h:351
void divide(float s)
Modifies a quaternion, scaling it by the provided parameter.
Definition: Quaternion.h:326
float getZ()
Accessor for the Quaternion&#39;s Z component value.
Definition: Quaternion.h:386
void conjugate()
Modifies the Quaternion to be its complex conjugate.
Definition: Quaternion.h:279
static void slerp(const Quaternion &qa, const Quaternion &qb, double t, Quaternion &out)
Estimates an intermediate Quaternion given Quaternions representing each end of the path...
Definition: Quaternion.h:237
Definition: IQuantity.h:33
Definition: Scalar.h:35
void getRoll(Scalar &roll)
Extracts the roll angle value from the Quaternion.
Definition: Quaternion.h:218
void getYawRadians(Scalar &yaw)
Extracts the yaw angle value from the Quaternion.
Definition: Quaternion.h:198
Definition: Unit.h:60
void getPitch(Scalar &pitch)
Extracts the pitch angle value from the Quaternion.
Definition: Quaternion.h:208
void set(float w, float x, float y, float z)
Modifies the Quaternion by setting the component W, X, Y and Z value.
Definition: Quaternion.h:131
Quaternion()
Constructs a Quaternion instance, using default values for a Unit Quaternion.
Definition: Quaternion.h:97
float getW()
Accessor for the Quaternion&#39;s W component value.
Definition: Quaternion.h:362
void inverse()
Modifies the Quaternion to be its inverse (reciprocal).
Definition: Quaternion.h:291