Transform.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 tf2_Transform_H
00018 #define tf2_Transform_H
00019 
00020 
00021 #include "Matrix3x3.h"
00022 
00023 
00024 namespace tf2
00025 {
00026 
00027 #define TransformData TransformDoubleData
00028 
00029 
00032 class Transform {
00033         
00035         Matrix3x3 m_basis;
00037         Vector3   m_origin;
00038 
00039 public:
00040         
00042         Transform() {}
00046         explicit TF2SIMD_FORCE_INLINE Transform(const Quaternion& q, 
00047                 const Vector3& c = Vector3(tf2Scalar(0), tf2Scalar(0), tf2Scalar(0))) 
00048                 : m_basis(q),
00049                 m_origin(c)
00050         {}
00051 
00055         explicit TF2SIMD_FORCE_INLINE Transform(const Matrix3x3& b, 
00056                 const Vector3& c = Vector3(tf2Scalar(0), tf2Scalar(0), tf2Scalar(0)))
00057                 : m_basis(b),
00058                 m_origin(c)
00059         {}
00061         TF2SIMD_FORCE_INLINE Transform (const Transform& other)
00062                 : m_basis(other.m_basis),
00063                 m_origin(other.m_origin)
00064         {
00065         }
00067         TF2SIMD_FORCE_INLINE Transform& operator=(const Transform& other)
00068         {
00069                 m_basis = other.m_basis;
00070                 m_origin = other.m_origin;
00071                 return *this;
00072         }
00073 
00078                 TF2SIMD_FORCE_INLINE void mult(const Transform& t1, const Transform& t2) {
00079                         m_basis = t1.m_basis * t2.m_basis;
00080                         m_origin = t1(t2.m_origin);
00081                 }
00082 
00083 /*              void multInverseLeft(const Transform& t1, const Transform& t2) {
00084                         Vector3 v = t2.m_origin - t1.m_origin;
00085                         m_basis = tf2MultTransposeLeft(t1.m_basis, t2.m_basis);
00086                         m_origin = v * t1.m_basis;
00087                 }
00088                 */
00089 
00091         TF2SIMD_FORCE_INLINE Vector3 operator()(const Vector3& x) const
00092         {
00093                 return Vector3(m_basis[0].dot(x) + m_origin.x(), 
00094                         m_basis[1].dot(x) + m_origin.y(), 
00095                         m_basis[2].dot(x) + m_origin.z());
00096         }
00097 
00099         TF2SIMD_FORCE_INLINE Vector3 operator*(const Vector3& x) const
00100         {
00101                 return (*this)(x);
00102         }
00103 
00105         TF2SIMD_FORCE_INLINE Quaternion operator*(const Quaternion& q) const
00106         {
00107                 return getRotation() * q;
00108         }
00109 
00111         TF2SIMD_FORCE_INLINE Matrix3x3&       getBasis()          { return m_basis; }
00113         TF2SIMD_FORCE_INLINE const Matrix3x3& getBasis()    const { return m_basis; }
00114 
00116         TF2SIMD_FORCE_INLINE Vector3&         getOrigin()         { return m_origin; }
00118         TF2SIMD_FORCE_INLINE const Vector3&   getOrigin()   const { return m_origin; }
00119 
00121         Quaternion getRotation() const { 
00122                 Quaternion q;
00123                 m_basis.getRotation(q);
00124                 return q;
00125         }
00126         
00127         
00130         void setFromOpenGLMatrix(const tf2Scalar *m)
00131         {
00132                 m_basis.setFromOpenGLSubMatrix(m);
00133                 m_origin.setValue(m[12],m[13],m[14]);
00134         }
00135 
00138         void getOpenGLMatrix(tf2Scalar *m) const 
00139         {
00140                 m_basis.getOpenGLSubMatrix(m);
00141                 m[12] = m_origin.x();
00142                 m[13] = m_origin.y();
00143                 m[14] = m_origin.z();
00144                 m[15] = tf2Scalar(1.0);
00145         }
00146 
00149         TF2SIMD_FORCE_INLINE void setOrigin(const Vector3& origin) 
00150         { 
00151                 m_origin = origin;
00152         }
00153 
00154         TF2SIMD_FORCE_INLINE Vector3 invXform(const Vector3& inVec) const;
00155 
00156 
00158         TF2SIMD_FORCE_INLINE void setBasis(const Matrix3x3& basis)
00159         { 
00160                 m_basis = basis;
00161         }
00162 
00164         TF2SIMD_FORCE_INLINE void setRotation(const Quaternion& q)
00165         {
00166                 m_basis.setRotation(q);
00167         }
00168 
00169 
00171         void setIdentity()
00172         {
00173                 m_basis.setIdentity();
00174                 m_origin.setValue(tf2Scalar(0.0), tf2Scalar(0.0), tf2Scalar(0.0));
00175         }
00176 
00179         Transform& operator*=(const Transform& t) 
00180         {
00181                 m_origin += m_basis * t.m_origin;
00182                 m_basis *= t.m_basis;
00183                 return *this;
00184         }
00185 
00187         Transform inverse() const
00188         { 
00189                 Matrix3x3 inv = m_basis.transpose();
00190                 return Transform(inv, inv * -m_origin);
00191         }
00192 
00196         Transform inverseTimes(const Transform& t) const;  
00197 
00199         Transform operator*(const Transform& t) const;
00200 
00202         static const Transform& getIdentity()
00203         {
00204                 static const Transform identityTransform(Matrix3x3::getIdentity());
00205                 return identityTransform;
00206         }
00207 
00208         void    serialize(struct        TransformData& dataOut) const;
00209 
00210         void    serializeFloat(struct   TransformFloatData& dataOut) const;
00211 
00212         void    deSerialize(const struct        TransformData& dataIn);
00213 
00214         void    deSerializeDouble(const struct  TransformDoubleData& dataIn);
00215 
00216         void    deSerializeFloat(const struct   TransformFloatData& dataIn);
00217 
00218 };
00219 
00220 
00221 TF2SIMD_FORCE_INLINE Vector3
00222 Transform::invXform(const Vector3& inVec) const
00223 {
00224         Vector3 v = inVec - m_origin;
00225         return (m_basis.transpose() * v);
00226 }
00227 
00228 TF2SIMD_FORCE_INLINE Transform 
00229 Transform::inverseTimes(const Transform& t) const  
00230 {
00231         Vector3 v = t.getOrigin() - m_origin;
00232                 return Transform(m_basis.transposeTimes(t.m_basis),
00233                         v * m_basis);
00234 }
00235 
00236 TF2SIMD_FORCE_INLINE Transform 
00237 Transform::operator*(const Transform& t) const
00238 {
00239         return Transform(m_basis * t.m_basis, 
00240                 (*this)(t.m_origin));
00241 }
00242 
00244 TF2SIMD_FORCE_INLINE bool operator==(const Transform& t1, const Transform& t2)
00245 {
00246    return ( t1.getBasis()  == t2.getBasis() &&
00247             t1.getOrigin() == t2.getOrigin() );
00248 }
00249 
00250 
00252 struct  TransformFloatData
00253 {
00254         Matrix3x3FloatData      m_basis;
00255         Vector3FloatData        m_origin;
00256 };
00257 
00258 struct  TransformDoubleData
00259 {
00260         Matrix3x3DoubleData     m_basis;
00261         Vector3DoubleData       m_origin;
00262 };
00263 
00264 
00265 
00266 TF2SIMD_FORCE_INLINE    void    Transform::serialize(TransformData& dataOut) const
00267 {
00268         m_basis.serialize(dataOut.m_basis);
00269         m_origin.serialize(dataOut.m_origin);
00270 }
00271 
00272 TF2SIMD_FORCE_INLINE    void    Transform::serializeFloat(TransformFloatData& dataOut) const
00273 {
00274         m_basis.serializeFloat(dataOut.m_basis);
00275         m_origin.serializeFloat(dataOut.m_origin);
00276 }
00277 
00278 
00279 TF2SIMD_FORCE_INLINE    void    Transform::deSerialize(const TransformData& dataIn)
00280 {
00281         m_basis.deSerialize(dataIn.m_basis);
00282         m_origin.deSerialize(dataIn.m_origin);
00283 }
00284 
00285 TF2SIMD_FORCE_INLINE    void    Transform::deSerializeFloat(const TransformFloatData& dataIn)
00286 {
00287         m_basis.deSerializeFloat(dataIn.m_basis);
00288         m_origin.deSerializeFloat(dataIn.m_origin);
00289 }
00290 
00291 TF2SIMD_FORCE_INLINE    void    Transform::deSerializeDouble(const TransformDoubleData& dataIn)
00292 {
00293         m_basis.deSerializeDouble(dataIn.m_basis);
00294         m_origin.deSerializeDouble(dataIn.m_origin);
00295 }
00296 
00297 }
00298 
00299 #endif
00300 
00301 
00302 
00303 
00304 
00305 


tf2
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Thu Jun 6 2019 20:22:56