Quaternion.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2015 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef _GAZEBO_MATH_QUATERNION_HH_
19 #define _GAZEBO_MATH_QUATERNION_HH_
20 
21 #include <math.h>
22 #include <iostream>
23 #include <cmath>
24 
25 #include "gazebo/math/Helpers.hh"
26 #include "gazebo/math/Angle.hh"
27 #include "gazebo/math/Vector3.hh"
28 #include "gazebo/math/Matrix3.hh"
29 #include "gazebo/math/Matrix4.hh"
30 #include "gazebo/util/system.hh"
31 
32 namespace gazebo
33 {
34  namespace math
35  {
38 
42  {
44  public: Quaternion();
45 
51  public: Quaternion(const double &_w, const double &_x, const double &_y,
52  const double &_z);
53 
58  public: Quaternion(const double &_roll, const double &_pitch,
59  const double &_yaw);
60 
64  public: Quaternion(const Vector3 &_axis, const double &_angle);
65 
68  public: Quaternion(const Vector3 &_rpy);
69 
72  public: Quaternion(const Quaternion &_qt);
73 
75  public: ~Quaternion();
76 
79  public: Quaternion &operator =(const Quaternion &_qt);
80 
82  public: void Invert();
83 
86  public: inline Quaternion GetInverse() const
87  {
88  double s = 0;
89  Quaternion q(this->w, this->x, this->y, this->z);
90 
91  // use s to test if quaternion is valid
92  s = q.w * q.w + q.x * q.x + q.y * q.y + q.z * q.z;
93 
94  if (math::equal(s, 0.0))
95  {
96  q.w = 1.0;
97  q.x = 0.0;
98  q.y = 0.0;
99  q.z = 0.0;
100  }
101  else
102  {
103  // deal with non-normalized quaternion
104  // div by s so q * qinv = identity
105  q.w = q.w / s;
106  q.x = -q.x / s;
107  q.y = -q.y / s;
108  q.z = -q.z / s;
109  }
110  return q;
111  }
112 
114  public: void SetToIdentity();
115 
118  public: Quaternion GetLog() const;
119 
122  public: Quaternion GetExp() const;
123 
125  public: void Normalize();
126 
132  public: void SetFromAxis(double _x, double _y, double _z, double _a);
133 
137  public: void SetFromAxis(const Vector3 &_axis, double _a);
138 
144  public: void Set(double _u, double _x, double _y, double _z);
145 
151  public: void SetFromEuler(const Vector3 &_vec);
152 
157  public: void SetFromEuler(double _roll, double _pitch, double _yaw);
158 
161  public: Vector3 GetAsEuler() const;
162 
166  public: static Quaternion EulerToQuaternion(const Vector3 &_vec);
167 
173  public: static Quaternion EulerToQuaternion(double _x,
174  double _y,
175  double _z);
176 
179  public: double GetRoll();
180 
183  public: double GetPitch();
184 
187  public: double GetYaw();
188 
192  public: void GetAsAxis(Vector3 &_axis, double &_angle) const;
193 
196  public: void Scale(double _scale);
197 
201  public: Quaternion operator+(const Quaternion &_qt) const;
202 
206  public: Quaternion operator+=(const Quaternion &_qt);
207 
211  public: Quaternion operator-(const Quaternion &_qt) const;
212 
216  public: Quaternion operator-=(const Quaternion &_qt);
217 
221  public: inline Quaternion operator*(const Quaternion &_q) const
222  {
223  return Quaternion(
224  this->w*_q.w - this->x*_q.x - this->y*_q.y - this->z*_q.z,
225  this->w*_q.x + this->x*_q.w + this->y*_q.z - this->z*_q.y,
226  this->w*_q.y - this->x*_q.z + this->y*_q.w + this->z*_q.x,
227  this->w*_q.z + this->x*_q.y - this->y*_q.x + this->z*_q.w);
228  }
229 
233  public: Quaternion operator*(const double &_f) const;
234 
238  public: Quaternion operator*=(const Quaternion &qt);
239 
243  public: Vector3 operator*(const Vector3 &_v) const;
244 
248  public: bool operator ==(const Quaternion &_qt) const;
249 
253  public: bool operator!=(const Quaternion &_qt) const;
254 
257  public: Quaternion operator-() const;
258 
262  public: inline Vector3 RotateVector(const Vector3 &_vec) const
263  {
264  Quaternion tmp(0.0, _vec.x, _vec.y, _vec.z);
265  tmp = (*this) * (tmp * this->GetInverse());
266  return Vector3(tmp.x, tmp.y, tmp.z);
267  }
268 
272  public: Vector3 RotateVectorReverse(Vector3 _vec) const;
273 
276  public: bool IsFinite() const;
277 
279  public: inline void Correct()
280  {
281  if (!std::isfinite(this->x))
282  this->x = 0;
283  if (!std::isfinite(this->y))
284  this->y = 0;
285  if (!std::isfinite(this->z))
286  this->z = 0;
287  if (!std::isfinite(this->w))
288  this->w = 1;
289 
290  if (math::equal(this->w, 0.0) &&
291  math::equal(this->x, 0.0) &&
292  math::equal(this->y, 0.0) &&
293  math::equal(this->z, 0.0))
294  {
295  this->w = 1;
296  }
297  }
298 
301  public: Matrix3 GetAsMatrix3() const;
302 
305  public: Matrix4 GetAsMatrix4() const;
306 
309  public: Vector3 GetXAxis() const;
310 
313  public: Vector3 GetYAxis() const;
314 
317  public: Vector3 GetZAxis() const;
318 
321  public: void Round(int _precision);
322 
326  public: double Dot(const Quaternion &_q) const;
327 
338  public: static Quaternion Squad(double _fT, const Quaternion &_rkP,
339  const Quaternion &_rkA, const Quaternion &_rkB,
340  const Quaternion &_rkQ, bool _shortestPath = false);
341 
350  public: static Quaternion Slerp(double _fT, const Quaternion &_rkP,
351  const Quaternion &_rkQ, bool _shortestPath = false);
352 
359  public: Quaternion Integrate(const Vector3 &_angularVelocity,
360  const double _deltaT) const;
361 
363  public: double w;
364 
366  public: double x;
367 
369  public: double y;
370 
372  public: double z;
373 
378  public: friend std::ostream &operator<<(std::ostream &_out,
379  const gazebo::math::Quaternion &_q)
380  {
381  Vector3 v(_q.GetAsEuler());
382  _out << precision(v.x, 6) << " " << precision(v.y, 6) << " "
383  << precision(v.z, 6);
384  return _out;
385  }
386 
391  public: friend std::istream &operator>>(std::istream &_in,
393  {
394  Angle roll, pitch, yaw;
395 
396  // Skip white spaces
397  _in.setf(std::ios_base::skipws);
398  _in >> roll >> pitch >> yaw;
399 
400  _q.SetFromEuler(Vector3(*roll, *pitch, *yaw));
401 
402  return _in;
403  }
404  };
406  }
407 }
408 #endif
double z
z value of the quaternion
Definition: Quaternion.hh:372
Forward declarations for the common classes.
Definition: Animation.hh:24
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:43
A 3x3 matrix class.
Definition: Matrix4.hh:39
double x
X location.
Definition: Vector3.hh:302
Vector3 RotateVector(const Vector3 &_vec) const
Rotate a vector using the quaternion.
Definition: Quaternion.hh:262
void SetFromEuler(const Vector3 &_vec)
Set the quaternion from Euler angles.
double z
Z location.
Definition: Vector3.hh:308
Quaternion operator*(const Quaternion &_q) const
Multiplication operator.
Definition: Quaternion.hh:221
bool equal(const T &_a, const T &_b, const T &_epsilon=1e-6)
check if two values are equal, within a tolerance
Definition: Helpers.hh:168
A 3x3 matrix class.
Definition: Matrix3.hh:34
void Correct()
Correct any nan values in this quaternion.
Definition: Quaternion.hh:279
double w
w value of the quaternion
Definition: Quaternion.hh:363
A quaternion class.
Definition: Quaternion.hh:41
friend std::istream & operator>>(std::istream &_in, gazebo::math::Quaternion &_q)
Stream extraction operator.
Definition: Quaternion.hh:391
GAZEBO_VISIBLE void Set(common::Image &_img, const msgs::Image &_msg)
Convert a msgs::Image to a common::Image.
double y
y value of the quaternion
Definition: Quaternion.hh:369
Quaternion GetInverse() const
Get the inverse of this quaternion.
Definition: Quaternion.hh:86
double x
x value of the quaternion
Definition: Quaternion.hh:366
T precision(const T &_a, const unsigned int &_precision)
get value at a specified precision
Definition: Helpers.hh:179
An angle and related functions.
Definition: Angle.hh:52
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:48
double y
Y location.
Definition: Vector3.hh:305
friend std::ostream & operator<<(std::ostream &_out, const gazebo::math::Quaternion &_q)
Stream insertion operator.
Definition: Quaternion.hh:378
Vector3 GetAsEuler() const
Return the rotation in Euler angles.