Quaternion.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans  http://continuousphysics.com/Bullet/
00003 
00004 This software is provided 'as-is', without any express or implied warranty.
00005 In no event will the authors be held liable for any damages arising from the use of this software.
00006 Permission is granted to anyone to use this software for any purpose, 
00007 including commercial applications, and to alter it and redistribute it freely, 
00008 subject to the following restrictions:
00009 
00010 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
00011 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
00012 3. This notice may not be removed or altered from any source distribution.
00013 */
00014 
00015 
00016 
00017 #ifndef TF_QUATERNION_H_
00018 #define TF_QUATERNION_H_
00019 
00020 
00021 #include "Vector3.h"
00022 #include "QuadWord.h"
00023 
00024 #include "LinearMath/btQuaternion.h"
00025 
00026 namespace tf
00027 {
00028 
00030 class Quaternion : public QuadWord {
00031 public:
00033         Quaternion() {}
00034 
00038         TFSIMD_FORCE_INLINE     Quaternion (const btQuaternion& q)
00039         {
00040           m_floats[0] = q.x(); m_floats[1] = q.y(); m_floats[2] = q.z(); m_floats[3] = q.w();
00041         }
00042 
00043         //              template <typename tfScalar>
00044         //              explicit Quaternion(const tfScalar *v) : Tuple4<tfScalar>(v) {}
00046         Quaternion(const tfScalar& x, const tfScalar& y, const tfScalar& z, const tfScalar& w) 
00047                 : QuadWord(x, y, z, w) 
00048         {}
00052         Quaternion(const Vector3& axis, const tfScalar& angle) 
00053         { 
00054                 setRotation(axis, angle); 
00055         }
00060   Quaternion(const tfScalar& yaw, const tfScalar& pitch, const tfScalar& roll) __attribute__((deprecated))
00061         { 
00062 #ifndef TF_EULER_DEFAULT_ZYX
00063                 setEuler(yaw, pitch, roll); 
00064 #else
00065                 setRPY(roll, pitch, yaw);
00066 #endif 
00067         }
00071         void setRotation(const Vector3& axis, const tfScalar& angle)
00072         {
00073                 tfScalar d = axis.length();
00074                 tfAssert(d != tfScalar(0.0));
00075                 tfScalar s = tfSin(angle * tfScalar(0.5)) / d;
00076                 setValue(axis.x() * s, axis.y() * s, axis.z() * s, 
00077                         tfCos(angle * tfScalar(0.5)));
00078         }
00083         void setEuler(const tfScalar& yaw, const tfScalar& pitch, const tfScalar& roll)
00084         {
00085                 tfScalar halfYaw = tfScalar(yaw) * tfScalar(0.5);  
00086                 tfScalar halfPitch = tfScalar(pitch) * tfScalar(0.5);  
00087                 tfScalar halfRoll = tfScalar(roll) * tfScalar(0.5);  
00088                 tfScalar cosYaw = tfCos(halfYaw);
00089                 tfScalar sinYaw = tfSin(halfYaw);
00090                 tfScalar cosPitch = tfCos(halfPitch);
00091                 tfScalar sinPitch = tfSin(halfPitch);
00092                 tfScalar cosRoll = tfCos(halfRoll);
00093                 tfScalar sinRoll = tfSin(halfRoll);
00094                 setValue(cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw,
00095                         cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw,
00096                         sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw,
00097                         cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw);
00098         }
00103   void setRPY(const tfScalar& roll, const tfScalar& pitch, const tfScalar& yaw)
00104         {
00105                 tfScalar halfYaw = tfScalar(yaw) * tfScalar(0.5);  
00106                 tfScalar halfPitch = tfScalar(pitch) * tfScalar(0.5);  
00107                 tfScalar halfRoll = tfScalar(roll) * tfScalar(0.5);  
00108                 tfScalar cosYaw = tfCos(halfYaw);
00109                 tfScalar sinYaw = tfSin(halfYaw);
00110                 tfScalar cosPitch = tfCos(halfPitch);
00111                 tfScalar sinPitch = tfSin(halfPitch);
00112                 tfScalar cosRoll = tfCos(halfRoll);
00113                 tfScalar sinRoll = tfSin(halfRoll);
00114                 setValue(sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw, //x
00115                          cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw, //y
00116                          cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw, //z
00117                          cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw); //formerly yzx
00118         }
00123   void setEulerZYX(const tfScalar& yaw, const tfScalar& pitch, const tfScalar& roll) __attribute__((deprecated))
00124         {
00125           setRPY(roll, pitch, yaw);
00126         }
00129         TFSIMD_FORCE_INLINE     Quaternion& operator+=(const Quaternion& q)
00130         {
00131                 m_floats[0] += q.x(); m_floats[1] += q.y(); m_floats[2] += q.z(); m_floats[3] += q.m_floats[3];
00132                 return *this;
00133         }
00134 
00135 
00139         TFSIMD_FORCE_INLINE     Quaternion& operator=(const btQuaternion& q)
00140         {
00141           m_floats[0] = q.x(); m_floats[1] = q.y(); m_floats[2] = q.z(); m_floats[3] = q.w();
00142                 return *this;
00143         }
00144 
00147         TFSIMD_FORCE_INLINE     btQuaternion as_bt() const __attribute__((deprecated)) { return asBt(); } ;
00148         TFSIMD_FORCE_INLINE     btQuaternion asBt() const
00149         {
00150           return btQuaternion(m_floats[0], m_floats[1], m_floats[2], m_floats[3]);
00151         }
00152 
00153   
00154 
00157         Quaternion& operator-=(const Quaternion& q) 
00158         {
00159                 m_floats[0] -= q.x(); m_floats[1] -= q.y(); m_floats[2] -= q.z(); m_floats[3] -= q.m_floats[3];
00160                 return *this;
00161         }
00162 
00165         Quaternion& operator*=(const tfScalar& s)
00166         {
00167                 m_floats[0] *= s; m_floats[1] *= s; m_floats[2] *= s; m_floats[3] *= s;
00168                 return *this;
00169         }
00170 
00174         Quaternion& operator*=(const Quaternion& q)
00175         {
00176                 setValue(m_floats[3] * q.x() + m_floats[0] * q.m_floats[3] + m_floats[1] * q.z() - m_floats[2] * q.y(),
00177                         m_floats[3] * q.y() + m_floats[1] * q.m_floats[3] + m_floats[2] * q.x() - m_floats[0] * q.z(),
00178                         m_floats[3] * q.z() + m_floats[2] * q.m_floats[3] + m_floats[0] * q.y() - m_floats[1] * q.x(),
00179                         m_floats[3] * q.m_floats[3] - m_floats[0] * q.x() - m_floats[1] * q.y() - m_floats[2] * q.z());
00180                 return *this;
00181         }
00184         tfScalar dot(const Quaternion& q) const
00185         {
00186                 return m_floats[0] * q.x() + m_floats[1] * q.y() + m_floats[2] * q.z() + m_floats[3] * q.m_floats[3];
00187         }
00188 
00190         tfScalar length2() const
00191         {
00192                 return dot(*this);
00193         }
00194 
00196         tfScalar length() const
00197         {
00198                 return tfSqrt(length2());
00199         }
00200 
00203         Quaternion& normalize() 
00204         {
00205                 return *this /= length();
00206         }
00207 
00210         TFSIMD_FORCE_INLINE Quaternion
00211         operator*(const tfScalar& s) const
00212         {
00213                 return Quaternion(x() * s, y() * s, z() * s, m_floats[3] * s);
00214         }
00215 
00216 
00219         Quaternion operator/(const tfScalar& s) const
00220         {
00221                 tfAssert(s != tfScalar(0.0));
00222                 return *this * (tfScalar(1.0) / s);
00223         }
00224 
00227         Quaternion& operator/=(const tfScalar& s) 
00228         {
00229                 tfAssert(s != tfScalar(0.0));
00230                 return *this *= tfScalar(1.0) / s;
00231         }
00232 
00234         Quaternion normalized() const 
00235         {
00236                 return *this / length();
00237         } 
00240         tfScalar angle(const Quaternion& q) const 
00241         {
00242                 tfScalar s = tfSqrt(length2() * q.length2());
00243                 tfAssert(s != tfScalar(0.0));
00244                 return tfAcos(dot(q) / s);
00245         }
00248         tfScalar angleShortestPath(const Quaternion& q) const 
00249         {
00250                 tfScalar s = tfSqrt(length2() * q.length2());
00251                 tfAssert(s != tfScalar(0.0));
00252                 if (dot(q) < 0) // Take care of long angle case see http://en.wikipedia.org/wiki/Slerp
00253                         return tfAcos(dot(-q) / s) * tfScalar(2.0);
00254                 else 
00255                         return tfAcos(dot(q) / s) * tfScalar(2.0);
00256         }
00258         tfScalar getAngle() const 
00259         {
00260                 tfScalar s = tfScalar(2.) * tfAcos(m_floats[3]);
00261                 return s;
00262         }
00263 
00265         tfScalar getAngleShortestPath() const 
00266         {
00267         tfScalar s;
00268                 if (dot(*this) < 0)
00269                         s = tfScalar(2.) * tfAcos(m_floats[3]);
00270                 else
00271                         s = tfScalar(2.) * tfAcos(-m_floats[3]);
00272 
00273                 return s;
00274         }
00275 
00277         Vector3 getAxis() const
00278         {
00279                 tfScalar s_squared = tfScalar(1.) - tfPow(m_floats[3], tfScalar(2.));
00280                 if (s_squared < tfScalar(10.) * TFSIMD_EPSILON) //Check for divide by zero
00281                         return Vector3(1.0, 0.0, 0.0);  // Arbitrary
00282                 tfScalar s = tfSqrt(s_squared);
00283                 return Vector3(m_floats[0] / s, m_floats[1] / s, m_floats[2] / s);
00284         }
00285 
00287         Quaternion inverse() const
00288         {
00289                 return Quaternion(-m_floats[0], -m_floats[1], -m_floats[2], m_floats[3]);
00290         }
00291 
00294         TFSIMD_FORCE_INLINE Quaternion
00295         operator+(const Quaternion& q2) const
00296         {
00297                 const Quaternion& q1 = *this;
00298                 return Quaternion(q1.x() + q2.x(), q1.y() + q2.y(), q1.z() + q2.z(), q1.m_floats[3] + q2.m_floats[3]);
00299         }
00300 
00303         TFSIMD_FORCE_INLINE Quaternion
00304         operator-(const Quaternion& q2) const
00305         {
00306                 const Quaternion& q1 = *this;
00307                 return Quaternion(q1.x() - q2.x(), q1.y() - q2.y(), q1.z() - q2.z(), q1.m_floats[3] - q2.m_floats[3]);
00308         }
00309 
00312         TFSIMD_FORCE_INLINE Quaternion operator-() const
00313         {
00314                 const Quaternion& q2 = *this;
00315                 return Quaternion( - q2.x(), - q2.y(),  - q2.z(),  - q2.m_floats[3]);
00316         }
00318         TFSIMD_FORCE_INLINE Quaternion farthest( const Quaternion& qd) const 
00319         {
00320                 Quaternion diff,sum;
00321                 diff = *this - qd;
00322                 sum = *this + qd;
00323                 if( diff.dot(diff) > sum.dot(sum) )
00324                         return qd;
00325                 return (-qd);
00326         }
00327 
00329         TFSIMD_FORCE_INLINE Quaternion nearest( const Quaternion& qd) const 
00330         {
00331                 Quaternion diff,sum;
00332                 diff = *this - qd;
00333                 sum = *this + qd;
00334                 if( diff.dot(diff) < sum.dot(sum) )
00335                         return qd;
00336                 return (-qd);
00337         }
00338 
00339 
00344         Quaternion slerp(const Quaternion& q, const tfScalar& t) const
00345         {
00346           tfScalar theta = angleShortestPath(q) / tfScalar(2.0);
00347                 if (theta != tfScalar(0.0))
00348                 {
00349                         tfScalar d = tfScalar(1.0) / tfSin(theta);
00350                         tfScalar s0 = tfSin((tfScalar(1.0) - t) * theta);
00351                         tfScalar s1 = tfSin(t * theta);   
00352                         if (dot(q) < 0) // Take care of long angle case see http://en.wikipedia.org/wiki/Slerp
00353                           return Quaternion((m_floats[0] * s0 + -q.x() * s1) * d,
00354                                               (m_floats[1] * s0 + -q.y() * s1) * d,
00355                                               (m_floats[2] * s0 + -q.z() * s1) * d,
00356                                               (m_floats[3] * s0 + -q.m_floats[3] * s1) * d);
00357                         else
00358                           return Quaternion((m_floats[0] * s0 + q.x() * s1) * d,
00359                                               (m_floats[1] * s0 + q.y() * s1) * d,
00360                                               (m_floats[2] * s0 + q.z() * s1) * d,
00361                                               (m_floats[3] * s0 + q.m_floats[3] * s1) * d);
00362                         
00363                 }
00364                 else
00365                 {
00366                         return *this;
00367                 }
00368         }
00369 
00370         static const Quaternion&        getIdentity()
00371         {
00372                 static const Quaternion identityQuat(tfScalar(0.),tfScalar(0.),tfScalar(0.),tfScalar(1.));
00373                 return identityQuat;
00374         }
00375 
00376         TFSIMD_FORCE_INLINE const tfScalar& getW() const { return m_floats[3]; }
00377 
00378         
00379 };
00380 
00381 
00383 TFSIMD_FORCE_INLINE Quaternion
00384 operator-(const Quaternion& q)
00385 {
00386         return Quaternion(-q.x(), -q.y(), -q.z(), -q.w());
00387 }
00388 
00389 
00390 
00392 TFSIMD_FORCE_INLINE Quaternion
00393 operator*(const Quaternion& q1, const Quaternion& q2) {
00394         return Quaternion(q1.w() * q2.x() + q1.x() * q2.w() + q1.y() * q2.z() - q1.z() * q2.y(),
00395                 q1.w() * q2.y() + q1.y() * q2.w() + q1.z() * q2.x() - q1.x() * q2.z(),
00396                 q1.w() * q2.z() + q1.z() * q2.w() + q1.x() * q2.y() - q1.y() * q2.x(),
00397                 q1.w() * q2.w() - q1.x() * q2.x() - q1.y() * q2.y() - q1.z() * q2.z()); 
00398 }
00399 
00400 TFSIMD_FORCE_INLINE Quaternion
00401 operator*(const Quaternion& q, const Vector3& w)
00402 {
00403         return Quaternion( q.w() * w.x() + q.y() * w.z() - q.z() * w.y(),
00404                 q.w() * w.y() + q.z() * w.x() - q.x() * w.z(),
00405                 q.w() * w.z() + q.x() * w.y() - q.y() * w.x(),
00406                 -q.x() * w.x() - q.y() * w.y() - q.z() * w.z()); 
00407 }
00408 
00409 TFSIMD_FORCE_INLINE Quaternion
00410 operator*(const Vector3& w, const Quaternion& q)
00411 {
00412         return Quaternion( w.x() * q.w() + w.y() * q.z() - w.z() * q.y(),
00413                 w.y() * q.w() + w.z() * q.x() - w.x() * q.z(),
00414                 w.z() * q.w() + w.x() * q.y() - w.y() * q.x(),
00415                 -w.x() * q.x() - w.y() * q.y() - w.z() * q.z()); 
00416 }
00417 
00419 TFSIMD_FORCE_INLINE tfScalar 
00420 dot(const Quaternion& q1, const Quaternion& q2) 
00421 { 
00422         return q1.dot(q2); 
00423 }
00424 
00425 
00427 TFSIMD_FORCE_INLINE tfScalar
00428 length(const Quaternion& q) 
00429 { 
00430         return q.length(); 
00431 }
00432 
00434 TFSIMD_FORCE_INLINE tfScalar
00435 angle(const Quaternion& q1, const Quaternion& q2) 
00436 { 
00437         return q1.angle(q2); 
00438 }
00439 
00441 TFSIMD_FORCE_INLINE tfScalar
00442 angleShortestPath(const Quaternion& q1, const Quaternion& q2) 
00443 { 
00444         return q1.angleShortestPath(q2); 
00445 }
00446 
00448 TFSIMD_FORCE_INLINE Quaternion
00449 inverse(const Quaternion& q) 
00450 {
00451         return q.inverse();
00452 }
00453 
00459 TFSIMD_FORCE_INLINE Quaternion
00460 slerp(const Quaternion& q1, const Quaternion& q2, const tfScalar& t) 
00461 {
00462         return q1.slerp(q2, t);
00463 }
00464 
00465 TFSIMD_FORCE_INLINE Vector3 
00466 quatRotate(const Quaternion& rotation, const Vector3& v) 
00467 {
00468         Quaternion q = rotation * v;
00469         q *= rotation.inverse();
00470         return Vector3(q.getX(),q.getY(),q.getZ());
00471 }
00472 
00473 TFSIMD_FORCE_INLINE Quaternion 
00474 shortestArcQuat(const Vector3& v0, const Vector3& v1) // Game Programming Gems 2.10. make sure v0,v1 are normalized
00475 {
00476         Vector3 c = v0.cross(v1);
00477         tfScalar  d = v0.dot(v1);
00478 
00479         if (d < -1.0 + TFSIMD_EPSILON)
00480         {
00481                 Vector3 n,unused;
00482                 tfPlaneSpace1(v0,n,unused);
00483                 return Quaternion(n.x(),n.y(),n.z(),0.0f); // just pick any vector that is orthogonal to v0
00484         }
00485 
00486         tfScalar  s = tfSqrt((1.0f + d) * 2.0f);
00487         tfScalar rs = 1.0f / s;
00488 
00489         return Quaternion(c.getX()*rs,c.getY()*rs,c.getZ()*rs,s * 0.5f);
00490 }
00491 
00492 TFSIMD_FORCE_INLINE Quaternion 
00493 shortestArcQuatNormalize2(Vector3& v0,Vector3& v1)
00494 {
00495         v0.normalize();
00496         v1.normalize();
00497         return shortestArcQuat(v0,v1);
00498 }
00499 
00500 }
00501 #endif
00502 
00503 
00504 
00505 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Thu Aug 22 2013 11:29:01