quat.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2016-2017, the mcl_3dl authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its 
00014  *       contributors may be used to endorse or promote products derived from 
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #ifndef MCL_3DL_QUAT_H
00031 #define MCL_3DL_QUAT_H
00032 
00033 #include <algorithm>
00034 
00035 #include <mcl_3dl/vec3.h>
00036 
00037 namespace mcl_3dl
00038 {
00039 class Quat
00040 {
00041 public:
00042   float x_;
00043   float y_;
00044   float z_;
00045   float w_;
00046 
00047   Quat(const float& x, const float& y, const float& z, const float& w)
00048   {
00049     x_ = x;
00050     y_ = y;
00051     z_ = z;
00052     w_ = w;
00053   }
00054   Quat(const Vec3& axis, const float& ang)
00055   {
00056     setAxisAng(axis, ang);
00057   }
00058   Quat(const Vec3& forward, const Vec3& up_raw)
00059   {
00060     const Vec3 xv = forward.normalized();
00061     const Vec3 yv = up_raw.cross(xv).normalized();
00062     const Vec3 zv = xv.cross(yv).normalized();
00063 
00064     w_ = sqrtf(std::max(0.0, 1.0 + xv.x_ + yv.y_ + zv.z_)) / 2.0;
00065     x_ = sqrtf(std::max(0.0, 1.0 + xv.x_ - yv.y_ - zv.z_)) / 2.0;
00066     y_ = sqrtf(std::max(0.0, 1.0 - xv.x_ + yv.y_ - zv.z_)) / 2.0;
00067     z_ = sqrtf(std::max(0.0, 1.0 - xv.x_ - yv.y_ + zv.z_)) / 2.0;
00068     if (zv.y_ - yv.z_ > 0)
00069       x_ = -x_;
00070     if (xv.z_ - zv.x_ > 0)
00071       y_ = -y_;
00072     if (yv.x_ - xv.y_ > 0)
00073       z_ = -z_;
00074   }
00075   explicit Quat(const Vec3& rpy)
00076   {
00077     setRPY(rpy);
00078   }
00079   Quat()
00080   {
00081     w_ = 1.0;
00082     x_ = y_ = z_ = 0.0;
00083   }
00084   float dot(const Quat& q) const
00085   {
00086     return x_ * q.x_ + y_ * q.y_ + z_ * q.z_ + w_ * q.w_;
00087   }
00088   float norm() const
00089   {
00090     return sqrtf(dot(*this));
00091   }
00092   bool operator==(const Quat& q) const
00093   {
00094     return x_ == q.x_ && y_ == q.y_ && z_ == q.z_ && w_ == q.w_;
00095   }
00096   bool operator!=(const Quat& q) const
00097   {
00098     return !operator==(q);
00099   }
00100   Quat operator+(const Quat& q) const
00101   {
00102     return Quat(x_ + q.x_, y_ + q.y_, z_ + q.z_, w_ + q.w_);
00103   }
00104   Quat operator+=(const Quat& q)
00105   {
00106     x_ += q.x_;
00107     y_ += q.y_;
00108     z_ += q.z_;
00109     w_ += q.w_;
00110     return *this;
00111   }
00112   Quat operator-(const Quat& q) const
00113   {
00114     return Quat(x_ - q.x_, y_ - q.y_, z_ - q.z_, w_ - q.w_);
00115   }
00116   Quat operator-=(const Quat& q)
00117   {
00118     x_ -= q.x_;
00119     y_ -= q.y_;
00120     z_ -= q.z_;
00121     w_ -= q.w_;
00122     return *this;
00123   }
00124   Quat operator-() const
00125   {
00126     return Quat(-x_, -y_, -z_, -w_);
00127   }
00128   Quat operator*(const Quat& q) const
00129   {
00130     return Quat(
00131         w_ * q.x_ + x_ * q.w_ + y_ * q.z_ - z_ * q.y_,
00132         w_ * q.y_ + y_ * q.w_ + z_ * q.x_ - x_ * q.z_,
00133         w_ * q.z_ + z_ * q.w_ + x_ * q.y_ - y_ * q.x_,
00134         w_ * q.w_ - x_ * q.x_ - y_ * q.y_ - z_ * q.z_);
00135   }
00136   Vec3 operator*(const Vec3& v) const
00137   {
00138     const Quat ret = *this * Quat(v.x_, v.y_, v.z_, 0.0) * conj();
00139     return Vec3(ret.x_, ret.y_, ret.z_);
00140   }
00141   Quat operator*(const float& s) const
00142   {
00143     return Quat(x_ * s, y_ * s, z_ * s, w_ * s);
00144   }
00145   Quat operator/(const float& s) const
00146   {
00147     return operator*(1.0 / s);
00148   }
00149   Quat operator*=(const float& s)
00150   {
00151     x_ *= s;
00152     y_ *= s;
00153     z_ *= s;
00154     w_ *= s;
00155     return *this;
00156   }
00157   Quat operator/=(const float& s)
00158   {
00159     x_ /= s;
00160     y_ /= s;
00161     z_ /= s;
00162     w_ /= s;
00163     return *this;
00164   }
00165   Quat weighted(const float& s) const
00166   {
00167     Vec3 axis;
00168     float ang;
00169     getAxisAng(axis, ang);
00170     return Quat(axis, ang * s);
00171   }
00172   Quat normalized() const
00173   {
00174     float n = norm();
00175     Quat ret = *this;
00176     ret.x_ /= n;
00177     ret.y_ /= n;
00178     ret.z_ /= n;
00179     ret.w_ /= n;
00180     return ret;
00181   }
00182   void normalize()
00183   {
00184     *this = normalized();
00185   }
00186   Quat conj() const
00187   {
00188     return Quat(-x_, -y_, -z_, w_);
00189   }
00190   Quat inv() const
00191   {
00192     return conj() / dot(*this);
00193   }
00194   Vec3 getRPY() const
00195   {
00196     const float ysq = y_ * y_;
00197     const float t0 = -2.0 * (ysq + z_ * z_) + 1.0;
00198     const float t1 = +2.0 * (x_ * y_ + w_ * z_);
00199     float t2 = -2.0 * (x_ * z_ - w_ * y_);
00200     const float t3 = +2.0 * (y_ * z_ + w_ * x_);
00201     const float t4 = -2.0 * (x_ * x_ + ysq) + 1.0;
00202 
00203     if (t2 > 1.0)
00204       t2 = 1.0;
00205     if (t2 < -1.0)
00206       t2 = -1.0;
00207 
00208     return Vec3(std::atan2(t3, t4), std::asin(t2), std::atan2(t1, t0));
00209   }
00210   void setRPY(const Vec3& rpy)
00211   {
00212     const float t2 = cos(rpy.x_ * 0.5);
00213     const float t3 = sin(rpy.x_ * 0.5);
00214     const float t4 = cos(rpy.y_ * 0.5);
00215     const float t5 = sin(rpy.y_ * 0.5);
00216     const float t0 = cos(rpy.z_ * 0.5);
00217     const float t1 = sin(rpy.z_ * 0.5);
00218 
00219     x_ = t0 * t3 * t4 - t1 * t2 * t5;
00220     y_ = t0 * t2 * t5 + t1 * t3 * t4;
00221     z_ = t1 * t2 * t4 - t0 * t3 * t5;
00222     w_ = t0 * t2 * t4 + t1 * t3 * t5;
00223   }
00224   void setAxisAng(const Vec3& axis, const float& ang)
00225   {
00226     const Vec3 a = axis / axis.norm();
00227     const float s = sinf(ang / 2.0);
00228     x_ = a.x_ * s;
00229     y_ = a.y_ * s;
00230     z_ = a.z_ * s;
00231     w_ = cosf(ang / 2.0);
00232     normalize();
00233   }
00234   void getAxisAng(Vec3& axis, float& ang) const
00235   {
00236     if (fabs(w_) >= 1.0 - 0.000001)
00237     {
00238       ang = 0.0;
00239       axis = Vec3(0.0, 0.0, 1.0);
00240       return;
00241     }
00242     ang = acosf(w_) * 2.0;
00243     if (ang > M_PI)
00244       ang -= 2.0 * M_PI;
00245     const float wsq = 1.0 - w_ * w_;
00246     axis = Vec3(x_, y_, z_) / sqrtf(wsq);
00247   }
00248   void rotateAxis(const Quat& r)
00249   {
00250     Vec3 axis;
00251     float ang;
00252     getAxisAng(axis, ang);
00253     setAxisAng(r * axis, ang);
00254   }
00255 };
00256 }  // namespace mcl_3dl
00257 
00258 #endif  // MCL_3DL_QUAT_H


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Jun 20 2019 20:04:43