quat.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2016-2017, the mcl_3dl authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef MCL_3DL_QUAT_H
31 #define MCL_3DL_QUAT_H
32 
33 #include <algorithm>
34 
35 #include <mcl_3dl/vec3.h>
36 
37 namespace mcl_3dl
38 {
39 class Quat
40 {
41 public:
42  float x_;
43  float y_;
44  float z_;
45  float w_;
46 
47  Quat(const float& x, const float& y, const float& z, const float& w)
48  {
49  x_ = x;
50  y_ = y;
51  z_ = z;
52  w_ = w;
53  }
54  Quat(const Vec3& axis, const float& ang)
55  {
56  setAxisAng(axis, ang);
57  }
58  Quat(const Vec3& forward, const Vec3& up_raw)
59  {
60  const Vec3 xv = forward.normalized();
61  const Vec3 yv = up_raw.cross(xv).normalized();
62  const Vec3 zv = xv.cross(yv).normalized();
63 
64  w_ = sqrtf(std::max(0.0, 1.0 + xv.x_ + yv.y_ + zv.z_)) / 2.0;
65  x_ = sqrtf(std::max(0.0, 1.0 + xv.x_ - yv.y_ - zv.z_)) / 2.0;
66  y_ = sqrtf(std::max(0.0, 1.0 - xv.x_ + yv.y_ - zv.z_)) / 2.0;
67  z_ = sqrtf(std::max(0.0, 1.0 - xv.x_ - yv.y_ + zv.z_)) / 2.0;
68  if (zv.y_ - yv.z_ > 0)
69  x_ = -x_;
70  if (xv.z_ - zv.x_ > 0)
71  y_ = -y_;
72  if (yv.x_ - xv.y_ > 0)
73  z_ = -z_;
74  }
75  explicit Quat(const Vec3& rpy)
76  {
77  setRPY(rpy);
78  }
79  Quat()
80  {
81  w_ = 1.0;
82  x_ = y_ = z_ = 0.0;
83  }
84  float dot(const Quat& q) const
85  {
86  return x_ * q.x_ + y_ * q.y_ + z_ * q.z_ + w_ * q.w_;
87  }
88  float norm() const
89  {
90  return sqrtf(dot(*this));
91  }
92  bool operator==(const Quat& q) const
93  {
94  return x_ == q.x_ && y_ == q.y_ && z_ == q.z_ && w_ == q.w_;
95  }
96  bool operator!=(const Quat& q) const
97  {
98  return !operator==(q);
99  }
100  Quat operator+(const Quat& q) const
101  {
102  return Quat(x_ + q.x_, y_ + q.y_, z_ + q.z_, w_ + q.w_);
103  }
104  Quat operator+=(const Quat& q)
105  {
106  x_ += q.x_;
107  y_ += q.y_;
108  z_ += q.z_;
109  w_ += q.w_;
110  return *this;
111  }
112  Quat operator-(const Quat& q) const
113  {
114  return Quat(x_ - q.x_, y_ - q.y_, z_ - q.z_, w_ - q.w_);
115  }
116  Quat operator-=(const Quat& q)
117  {
118  x_ -= q.x_;
119  y_ -= q.y_;
120  z_ -= q.z_;
121  w_ -= q.w_;
122  return *this;
123  }
124  Quat operator-() const
125  {
126  return Quat(-x_, -y_, -z_, -w_);
127  }
128  Quat operator*(const Quat& q) const
129  {
130  return Quat(
131  w_ * q.x_ + x_ * q.w_ + y_ * q.z_ - z_ * q.y_,
132  w_ * q.y_ + y_ * q.w_ + z_ * q.x_ - x_ * q.z_,
133  w_ * q.z_ + z_ * q.w_ + x_ * q.y_ - y_ * q.x_,
134  w_ * q.w_ - x_ * q.x_ - y_ * q.y_ - z_ * q.z_);
135  }
136  Vec3 operator*(const Vec3& v) const
137  {
138  const Quat ret = *this * Quat(v.x_, v.y_, v.z_, 0.0) * conj();
139  return Vec3(ret.x_, ret.y_, ret.z_);
140  }
141  Quat operator*(const float& s) const
142  {
143  return Quat(x_ * s, y_ * s, z_ * s, w_ * s);
144  }
145  Quat operator/(const float& s) const
146  {
147  return operator*(1.0 / s);
148  }
149  Quat operator*=(const float& s)
150  {
151  x_ *= s;
152  y_ *= s;
153  z_ *= s;
154  w_ *= s;
155  return *this;
156  }
157  Quat operator/=(const float& s)
158  {
159  x_ /= s;
160  y_ /= s;
161  z_ /= s;
162  w_ /= s;
163  return *this;
164  }
165  Quat weighted(const float& s) const
166  {
167  Vec3 axis;
168  float ang;
169  getAxisAng(axis, ang);
170  return Quat(axis, ang * s);
171  }
172  Quat normalized() const
173  {
174  float n = norm();
175  Quat ret = *this;
176  ret.x_ /= n;
177  ret.y_ /= n;
178  ret.z_ /= n;
179  ret.w_ /= n;
180  return ret;
181  }
182  void normalize()
183  {
184  *this = normalized();
185  }
186  Quat conj() const
187  {
188  return Quat(-x_, -y_, -z_, w_);
189  }
190  Quat inv() const
191  {
192  return conj() / dot(*this);
193  }
194  Vec3 getRPY() const
195  {
196  const float ysq = y_ * y_;
197  const float t0 = -2.0 * (ysq + z_ * z_) + 1.0;
198  const float t1 = +2.0 * (x_ * y_ + w_ * z_);
199  float t2 = -2.0 * (x_ * z_ - w_ * y_);
200  const float t3 = +2.0 * (y_ * z_ + w_ * x_);
201  const float t4 = -2.0 * (x_ * x_ + ysq) + 1.0;
202 
203  if (t2 > 1.0)
204  t2 = 1.0;
205  if (t2 < -1.0)
206  t2 = -1.0;
207 
208  return Vec3(std::atan2(t3, t4), std::asin(t2), std::atan2(t1, t0));
209  }
210  void setRPY(const Vec3& rpy)
211  {
212  const float t2 = cos(rpy.x_ * 0.5);
213  const float t3 = sin(rpy.x_ * 0.5);
214  const float t4 = cos(rpy.y_ * 0.5);
215  const float t5 = sin(rpy.y_ * 0.5);
216  const float t0 = cos(rpy.z_ * 0.5);
217  const float t1 = sin(rpy.z_ * 0.5);
218 
219  x_ = t0 * t3 * t4 - t1 * t2 * t5;
220  y_ = t0 * t2 * t5 + t1 * t3 * t4;
221  z_ = t1 * t2 * t4 - t0 * t3 * t5;
222  w_ = t0 * t2 * t4 + t1 * t3 * t5;
223  }
224  void setAxisAng(const Vec3& axis, const float& ang)
225  {
226  const Vec3 a = axis / axis.norm();
227  const float s = sinf(ang / 2.0);
228  x_ = a.x_ * s;
229  y_ = a.y_ * s;
230  z_ = a.z_ * s;
231  w_ = cosf(ang / 2.0);
232  normalize();
233  }
234  void getAxisAng(Vec3& axis, float& ang) const
235  {
236  if (fabs(w_) >= 1.0 - 0.000001)
237  {
238  ang = 0.0;
239  axis = Vec3(0.0, 0.0, 1.0);
240  return;
241  }
242  ang = acosf(w_) * 2.0;
243  if (ang > M_PI)
244  ang -= 2.0 * M_PI;
245  const float wsq = 1.0 - w_ * w_;
246  axis = Vec3(x_, y_, z_) / sqrtf(wsq);
247  }
248  void rotateAxis(const Quat& r)
249  {
250  Vec3 axis;
251  float ang;
252  getAxisAng(axis, ang);
253  setAxisAng(r * axis, ang);
254  }
255 };
256 } // namespace mcl_3dl
257 
258 #endif // MCL_3DL_QUAT_H
float z_
Definition: vec3.h:40
void setAxisAng(const Vec3 &axis, const float &ang)
Definition: quat.h:224
Quat operator/=(const float &s)
Definition: quat.h:157
Quat conj() const
Definition: quat.h:186
bool operator==(const Quat &q) const
Definition: quat.h:92
bool operator!=(const Quat &q) const
Definition: quat.h:96
float y_
Definition: quat.h:43
XmlRpcServer s
Quat operator-() const
Definition: quat.h:124
Quat(const float &x, const float &y, const float &z, const float &w)
Definition: quat.h:47
float norm() const
Definition: vec3.h:149
Quat operator-=(const Quat &q)
Definition: quat.h:116
Quat operator+(const Quat &q) const
Definition: quat.h:100
Quat operator*(const float &s) const
Definition: quat.h:141
Quat(const Vec3 &rpy)
Definition: quat.h:75
Quat(const Vec3 &forward, const Vec3 &up_raw)
Definition: quat.h:58
void normalize()
Definition: quat.h:182
Vec3 cross(const Vec3 &q) const
Definition: vec3.h:139
float w_
Definition: quat.h:45
float y_
Definition: vec3.h:39
void getAxisAng(Vec3 &axis, float &ang) const
Definition: quat.h:234
Quat operator*=(const float &s)
Definition: quat.h:149
Quat normalized() const
Definition: quat.h:172
Quat inv() const
Definition: quat.h:190
float dot(const Quat &q) const
Definition: quat.h:84
float x_
Definition: vec3.h:38
Quat(const Vec3 &axis, const float &ang)
Definition: quat.h:54
Quat operator*(const Quat &q) const
Definition: quat.h:128
Vec3 normalized() const
Definition: vec3.h:153
Vec3 operator*(const Vec3 &v) const
Definition: quat.h:136
void setRPY(const Vec3 &rpy)
Definition: quat.h:210
Quat operator+=(const Quat &q)
Definition: quat.h:104
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
Quat weighted(const float &s) const
Definition: quat.h:165
Quat operator-(const Quat &q) const
Definition: quat.h:112
Quat operator/(const float &s) const
Definition: quat.h:145
Vec3 getRPY() const
Definition: quat.h:194
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
float norm() const
Definition: quat.h:88
float z_
Definition: quat.h:44
float x_
Definition: quat.h:42
void rotateAxis(const Quat &r)
Definition: quat.h:248


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 8 2019 03:32:36