Go to the documentation of this file.
30 #ifndef MCL_3DL_QUAT_H
31 #define MCL_3DL_QUAT_H
48 inline constexpr
Quat(
const float& x,
const float& y,
const float& z,
const float& w)
55 inline Quat(
const Vec3& axis,
const float& ang)
65 w_ = std::sqrt(std::max(0.0, 1.0 + xv.
x_ + yv.
y_ + zv.
z_)) / 2.0;
66 x_ = std::sqrt(std::max(0.0, 1.0 + xv.
x_ - yv.
y_ - zv.
z_)) / 2.0;
67 y_ = std::sqrt(std::max(0.0, 1.0 - xv.
x_ + yv.
y_ - zv.
z_)) / 2.0;
68 z_ = std::sqrt(std::max(0.0, 1.0 - xv.
x_ - yv.
y_ + zv.
z_)) / 2.0;
69 if (zv.
y_ - yv.
z_ > 0)
71 if (xv.
z_ - zv.
x_ > 0)
73 if (yv.
x_ - xv.
y_ > 0)
87 inline constexpr
float dot(
const Quat& q)
const
93 return std::sqrt(
dot(*
this));
173 return Quat(axis, ang *
s);
177 return (*
this) /
norm();
193 const float ysq =
y_ *
y_;
194 const float t0 = -2.0 * (ysq +
z_ *
z_) + 1.0;
195 const float t1 = +2.0 * (
x_ *
y_ +
w_ *
z_);
196 const float t2 = std::max(-1.0, std::min(1.0, -2.0 * (
x_ *
z_ -
w_ *
y_)));
197 const float t3 = +2.0 * (
y_ *
z_ +
w_ *
x_);
198 const float t4 = -2.0 * (
x_ *
x_ + ysq) + 1.0;
200 return Vec3(std::atan2(t3, t4), std::asin(t2), std::atan2(t1, t0));
204 const float t2 = std::cos(rpy.
x_ / 2);
205 const float t3 = std::sin(rpy.
x_ / 2);
206 const float t4 = std::cos(rpy.
y_ / 2);
207 const float t5 = std::sin(rpy.
y_ / 2);
208 const float t0 = std::cos(rpy.
z_ / 2);
209 const float t1 = std::sin(rpy.
z_ / 2);
211 x_ = t0 * t3 * t4 - t1 * t2 * t5;
212 y_ = t0 * t2 * t5 + t1 * t3 * t4;
213 z_ = t1 * t2 * t4 - t0 * t3 * t5;
214 w_ = t0 * t2 * t4 + t1 * t3 * t5;
219 const float s = std::sin(ang / 2);
223 w_ = std::cos(ang / 2);
228 if (fabs(
w_) >= 1.0 - 0.000001)
231 axis =
Vec3(0.0, 0.0, 1.0);
234 ang = std::acos(
w_) * 2.0;
237 const float wsq = 1.0 -
w_ *
w_;
250 #endif // MCL_3DL_QUAT_H
constexpr bool operator==(const Quat &q) const
void setRPY(const Vec3 &rpy)
void rotateAxis(const Quat &r)
Quat operator+(const Quat &q) const
Quat weighted(const float &s) const
void setAxisAng(const Vec3 &axis, const float &ang)
constexpr Quat operator*(const float &s) const
constexpr Quat inv() const
Quat operator/=(const float &s)
constexpr Quat operator/(const float &s) const
constexpr Vec3 getRPY() const
constexpr float dot(const Quat &q) const
Quat(const Vec3 &forward, const Vec3 &up_raw)
Quat(const Vec3 &axis, const float &ang)
constexpr Quat(const float &x, const float &y, const float &z, const float &w)
Quat operator-=(const Quat &q)
void getAxisAng(Vec3 &axis, float &ang) const
constexpr Quat operator*(const Quat &q) const
constexpr Vec3 cross(const Vec3 &q) const
Quat operator*=(const float &s)
constexpr Quat conj() const
Vec3 operator*(const Vec3 &v) const
Quat operator+=(const Quat &q)
constexpr bool operator!=(const Quat &q) const
Quat operator-(const Quat &q) const
constexpr Quat operator-() const
mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Oct 17 2024 02:18:04