30 #ifndef MCL_3DL_QUAT_H 31 #define MCL_3DL_QUAT_H 47 Quat(
const float& x,
const float& y,
const float& z,
const float& w)
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)
70 if (xv.
z_ - zv.
x_ > 0)
72 if (yv.
x_ - xv.
y_ > 0)
86 return x_ * q.
x_ + y_ * q.
y_ + z_ * q.
z_ + w_ * q.
w_;
90 return sqrtf(
dot(*
this));
94 return x_ == q.
x_ && y_ == q.
y_ && z_ == q.
z_ && w_ == q.
w_;
102 return Quat(x_ + q.
x_, y_ + q.
y_, z_ + q.
z_, w_ + q.
w_);
114 return Quat(x_ - q.
x_, y_ - q.
y_, z_ - q.
z_, w_ - q.
w_);
126 return Quat(-x_, -y_, -z_, -w_);
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_);
143 return Quat(x_ * s, y_ * s, z_ * s, w_ * s);
170 return Quat(axis, ang * s);
188 return Quat(-x_, -y_, -z_, w_);
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;
208 return Vec3(std::atan2(t3, t4), std::asin(t2), std::atan2(t1, t0));
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);
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;
227 const float s = sinf(ang / 2.0);
231 w_ = cosf(ang / 2.0);
236 if (fabs(w_) >= 1.0 - 0.000001)
239 axis =
Vec3(0.0, 0.0, 1.0);
242 ang = acosf(w_) * 2.0;
245 const float wsq = 1.0 - w_ *
w_;
246 axis =
Vec3(x_, y_, z_) / sqrtf(wsq);
258 #endif // MCL_3DL_QUAT_H
void setAxisAng(const Vec3 &axis, const float &ang)
Quat operator/=(const float &s)
bool operator==(const Quat &q) const
bool operator!=(const Quat &q) const
Quat(const float &x, const float &y, const float &z, const float &w)
Quat operator-=(const Quat &q)
Quat operator+(const Quat &q) const
Quat operator*(const float &s) const
Quat(const Vec3 &forward, const Vec3 &up_raw)
Vec3 cross(const Vec3 &q) const
void getAxisAng(Vec3 &axis, float &ang) const
Quat operator*=(const float &s)
float dot(const Quat &q) const
Quat(const Vec3 &axis, const float &ang)
Quat operator*(const Quat &q) const
Vec3 operator*(const Vec3 &v) const
void setRPY(const Vec3 &rpy)
Quat operator+=(const Quat &q)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
Quat weighted(const float &s) const
Quat operator-(const Quat &q) const
Quat operator/(const float &s) const
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
void rotateAxis(const Quat &r)