Vector3.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_VECTOR3_H
00018 #define TF2_VECTOR3_H
00019 
00020 
00021 #include "Scalar.h"
00022 #include "MinMax.h"
00023 
00024 namespace tf2
00025 {
00026 
00027 #define Vector3Data Vector3DoubleData
00028 #define Vector3DataName "Vector3DoubleData"
00029 
00030 
00031 
00032 
00037 ATTRIBUTE_ALIGNED16(class) Vector3
00038 {
00039 public:
00040 
00041 #if defined (__SPU__) && defined (__CELLOS_LV2__)
00042                 tf2Scalar       m_floats[4];
00043 public:
00044         TF2SIMD_FORCE_INLINE const vec_float4&  get128() const
00045         {
00046                 return *((const vec_float4*)&m_floats[0]);
00047         }
00048 public:
00049 #else //__CELLOS_LV2__ __SPU__
00050 #ifdef TF2_USE_SSE // _WIN32
00051         union {
00052                 __m128 mVec128;
00053                 tf2Scalar       m_floats[4];
00054         };
00055         TF2SIMD_FORCE_INLINE    __m128  get128() const
00056         {
00057                 return mVec128;
00058         }
00059         TF2SIMD_FORCE_INLINE    void    set128(__m128 v128)
00060         {
00061                 mVec128 = v128;
00062         }
00063 #else
00064         tf2Scalar       m_floats[4];
00065 #endif
00066 #endif //__CELLOS_LV2__ __SPU__
00067 
00068         public:
00069 
00071         TF2SIMD_FORCE_INLINE Vector3() {}
00072 
00073  
00074         
00080         TF2SIMD_FORCE_INLINE Vector3(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z)
00081         {
00082                 m_floats[0] = x;
00083                 m_floats[1] = y;
00084                 m_floats[2] = z;
00085                 m_floats[3] = tf2Scalar(0.);
00086         }
00087 
00090         TF2SIMD_FORCE_INLINE Vector3& operator+=(const Vector3& v)
00091         {
00092 
00093                 m_floats[0] += v.m_floats[0]; m_floats[1] += v.m_floats[1];m_floats[2] += v.m_floats[2];
00094                 return *this;
00095         }
00096 
00097 
00100         TF2SIMD_FORCE_INLINE Vector3& operator-=(const Vector3& v) 
00101         {
00102                 m_floats[0] -= v.m_floats[0]; m_floats[1] -= v.m_floats[1];m_floats[2] -= v.m_floats[2];
00103                 return *this;
00104         }
00107         TF2SIMD_FORCE_INLINE Vector3& operator*=(const tf2Scalar& s)
00108         {
00109                 m_floats[0] *= s; m_floats[1] *= s;m_floats[2] *= s;
00110                 return *this;
00111         }
00112 
00115         TF2SIMD_FORCE_INLINE Vector3& operator/=(const tf2Scalar& s) 
00116         {
00117                 tf2FullAssert(s != tf2Scalar(0.0));
00118                 return *this *= tf2Scalar(1.0) / s;
00119         }
00120 
00123         TF2SIMD_FORCE_INLINE tf2Scalar dot(const Vector3& v) const
00124         {
00125                 return m_floats[0] * v.m_floats[0] + m_floats[1] * v.m_floats[1] +m_floats[2] * v.m_floats[2];
00126         }
00127 
00129         TF2SIMD_FORCE_INLINE tf2Scalar length2() const
00130         {
00131                 return dot(*this);
00132         }
00133 
00135         TF2SIMD_FORCE_INLINE tf2Scalar length() const
00136         {
00137                 return tf2Sqrt(length2());
00138         }
00139 
00142         TF2SIMD_FORCE_INLINE tf2Scalar distance2(const Vector3& v) const;
00143 
00146         TF2SIMD_FORCE_INLINE tf2Scalar distance(const Vector3& v) const;
00147 
00150         TF2SIMD_FORCE_INLINE Vector3& normalize() 
00151         {
00152                 return *this /= length();
00153         }
00154 
00156         TF2SIMD_FORCE_INLINE Vector3 normalized() const;
00157 
00161         TF2SIMD_FORCE_INLINE Vector3 rotate( const Vector3& wAxis, const tf2Scalar angle ) const;
00162 
00165         TF2SIMD_FORCE_INLINE tf2Scalar angle(const Vector3& v) const 
00166         {
00167                 tf2Scalar s = tf2Sqrt(length2() * v.length2());
00168                 tf2FullAssert(s != tf2Scalar(0.0));
00169                 return tf2Acos(dot(v) / s);
00170         }
00172         TF2SIMD_FORCE_INLINE Vector3 absolute() const 
00173         {
00174                 return Vector3(
00175                         tf2Fabs(m_floats[0]), 
00176                         tf2Fabs(m_floats[1]), 
00177                         tf2Fabs(m_floats[2]));
00178         }
00181         TF2SIMD_FORCE_INLINE Vector3 cross(const Vector3& v) const
00182         {
00183                 return Vector3(
00184                         m_floats[1] * v.m_floats[2] -m_floats[2] * v.m_floats[1],
00185                         m_floats[2] * v.m_floats[0] - m_floats[0] * v.m_floats[2],
00186                         m_floats[0] * v.m_floats[1] - m_floats[1] * v.m_floats[0]);
00187         }
00188 
00189         TF2SIMD_FORCE_INLINE tf2Scalar triple(const Vector3& v1, const Vector3& v2) const
00190         {
00191                 return m_floats[0] * (v1.m_floats[1] * v2.m_floats[2] - v1.m_floats[2] * v2.m_floats[1]) + 
00192                         m_floats[1] * (v1.m_floats[2] * v2.m_floats[0] - v1.m_floats[0] * v2.m_floats[2]) + 
00193                         m_floats[2] * (v1.m_floats[0] * v2.m_floats[1] - v1.m_floats[1] * v2.m_floats[0]);
00194         }
00195 
00198         TF2SIMD_FORCE_INLINE int minAxis() const
00199         {
00200                 return m_floats[0] < m_floats[1] ? (m_floats[0] <m_floats[2] ? 0 : 2) : (m_floats[1] <m_floats[2] ? 1 : 2);
00201         }
00202 
00205         TF2SIMD_FORCE_INLINE int maxAxis() const 
00206         {
00207                 return m_floats[0] < m_floats[1] ? (m_floats[1] <m_floats[2] ? 2 : 1) : (m_floats[0] <m_floats[2] ? 2 : 0);
00208         }
00209 
00210         TF2SIMD_FORCE_INLINE int furthestAxis() const
00211         {
00212                 return absolute().minAxis();
00213         }
00214 
00215         TF2SIMD_FORCE_INLINE int closestAxis() const 
00216         {
00217                 return absolute().maxAxis();
00218         }
00219 
00220         TF2SIMD_FORCE_INLINE void setInterpolate3(const Vector3& v0, const Vector3& v1, tf2Scalar rt)
00221         {
00222                 tf2Scalar s = tf2Scalar(1.0) - rt;
00223                 m_floats[0] = s * v0.m_floats[0] + rt * v1.m_floats[0];
00224                 m_floats[1] = s * v0.m_floats[1] + rt * v1.m_floats[1];
00225                 m_floats[2] = s * v0.m_floats[2] + rt * v1.m_floats[2];
00226                 //don't do the unused w component
00227                 //              m_co[3] = s * v0[3] + rt * v1[3];
00228         }
00229 
00233         TF2SIMD_FORCE_INLINE Vector3 lerp(const Vector3& v, const tf2Scalar& t) const 
00234         {
00235                 return Vector3(m_floats[0] + (v.m_floats[0] - m_floats[0]) * t,
00236                         m_floats[1] + (v.m_floats[1] - m_floats[1]) * t,
00237                         m_floats[2] + (v.m_floats[2] -m_floats[2]) * t);
00238         }
00239 
00242         TF2SIMD_FORCE_INLINE Vector3& operator*=(const Vector3& v)
00243         {
00244                 m_floats[0] *= v.m_floats[0]; m_floats[1] *= v.m_floats[1];m_floats[2] *= v.m_floats[2];
00245                 return *this;
00246         }
00247 
00249                 TF2SIMD_FORCE_INLINE const tf2Scalar& getX() const { return m_floats[0]; }
00251                 TF2SIMD_FORCE_INLINE const tf2Scalar& getY() const { return m_floats[1]; }
00253                 TF2SIMD_FORCE_INLINE const tf2Scalar& getZ() const { return m_floats[2]; }
00255                 TF2SIMD_FORCE_INLINE void       setX(tf2Scalar x) { m_floats[0] = x;};
00257                 TF2SIMD_FORCE_INLINE void       setY(tf2Scalar y) { m_floats[1] = y;};
00259                 TF2SIMD_FORCE_INLINE void       setZ(tf2Scalar z) {m_floats[2] = z;};
00261                 TF2SIMD_FORCE_INLINE void       setW(tf2Scalar w) { m_floats[3] = w;};
00263                 TF2SIMD_FORCE_INLINE const tf2Scalar& x() const { return m_floats[0]; }
00265                 TF2SIMD_FORCE_INLINE const tf2Scalar& y() const { return m_floats[1]; }
00267                 TF2SIMD_FORCE_INLINE const tf2Scalar& z() const { return m_floats[2]; }
00269                 TF2SIMD_FORCE_INLINE const tf2Scalar& w() const { return m_floats[3]; }
00270 
00271         //TF2SIMD_FORCE_INLINE tf2Scalar&       operator[](int i)       { return (&m_floats[0])[i];     }      
00272         //TF2SIMD_FORCE_INLINE const tf2Scalar& operator[](int i) const { return (&m_floats[0])[i]; }
00274         TF2SIMD_FORCE_INLINE    operator       tf2Scalar *()       { return &m_floats[0]; }
00275         TF2SIMD_FORCE_INLINE    operator const tf2Scalar *() const { return &m_floats[0]; }
00276 
00277         TF2SIMD_FORCE_INLINE    bool    operator==(const Vector3& other) const
00278         {
00279                 return ((m_floats[3]==other.m_floats[3]) && (m_floats[2]==other.m_floats[2]) && (m_floats[1]==other.m_floats[1]) && (m_floats[0]==other.m_floats[0]));
00280         }
00281 
00282         TF2SIMD_FORCE_INLINE    bool    operator!=(const Vector3& other) const
00283         {
00284                 return !(*this == other);
00285         }
00286 
00290                 TF2SIMD_FORCE_INLINE void       setMax(const Vector3& other)
00291                 {
00292                         tf2SetMax(m_floats[0], other.m_floats[0]);
00293                         tf2SetMax(m_floats[1], other.m_floats[1]);
00294                         tf2SetMax(m_floats[2], other.m_floats[2]);
00295                         tf2SetMax(m_floats[3], other.w());
00296                 }
00300                 TF2SIMD_FORCE_INLINE void       setMin(const Vector3& other)
00301                 {
00302                         tf2SetMin(m_floats[0], other.m_floats[0]);
00303                         tf2SetMin(m_floats[1], other.m_floats[1]);
00304                         tf2SetMin(m_floats[2], other.m_floats[2]);
00305                         tf2SetMin(m_floats[3], other.w());
00306                 }
00307 
00308                 TF2SIMD_FORCE_INLINE void       setValue(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z)
00309                 {
00310                         m_floats[0]=x;
00311                         m_floats[1]=y;
00312                         m_floats[2]=z;
00313                         m_floats[3] = tf2Scalar(0.);
00314                 }
00315 
00316                 void    getSkewSymmetricMatrix(Vector3* v0,Vector3* v1,Vector3* v2) const
00317                 {
00318                         v0->setValue(0.         ,-z()           ,y());
00319                         v1->setValue(z()        ,0.                     ,-x());
00320                         v2->setValue(-y()       ,x()    ,0.);
00321                 }
00322 
00323                 void    setZero()
00324                 {
00325                         setValue(tf2Scalar(0.),tf2Scalar(0.),tf2Scalar(0.));
00326                 }
00327 
00328                 TF2SIMD_FORCE_INLINE bool isZero() const 
00329                 {
00330                         return m_floats[0] == tf2Scalar(0) && m_floats[1] == tf2Scalar(0) && m_floats[2] == tf2Scalar(0);
00331                 }
00332 
00333                 TF2SIMD_FORCE_INLINE bool fuzzyZero() const 
00334                 {
00335                         return length2() < TF2SIMD_EPSILON;
00336                 }
00337 
00338                 TF2SIMD_FORCE_INLINE    void    serialize(struct        Vector3Data& dataOut) const;
00339 
00340                 TF2SIMD_FORCE_INLINE    void    deSerialize(const struct        Vector3Data& dataIn);
00341 
00342                 TF2SIMD_FORCE_INLINE    void    serializeFloat(struct   Vector3FloatData& dataOut) const;
00343 
00344                 TF2SIMD_FORCE_INLINE    void    deSerializeFloat(const struct   Vector3FloatData& dataIn);
00345 
00346                 TF2SIMD_FORCE_INLINE    void    serializeDouble(struct  Vector3DoubleData& dataOut) const;
00347 
00348                 TF2SIMD_FORCE_INLINE    void    deSerializeDouble(const struct  Vector3DoubleData& dataIn);
00349 
00350 };
00351 
00353 TF2SIMD_FORCE_INLINE Vector3 
00354 operator+(const Vector3& v1, const Vector3& v2) 
00355 {
00356         return Vector3(v1.m_floats[0] + v2.m_floats[0], v1.m_floats[1] + v2.m_floats[1], v1.m_floats[2] + v2.m_floats[2]);
00357 }
00358 
00360 TF2SIMD_FORCE_INLINE Vector3 
00361 operator*(const Vector3& v1, const Vector3& v2) 
00362 {
00363         return Vector3(v1.m_floats[0] * v2.m_floats[0], v1.m_floats[1] * v2.m_floats[1], v1.m_floats[2] * v2.m_floats[2]);
00364 }
00365 
00367 TF2SIMD_FORCE_INLINE Vector3 
00368 operator-(const Vector3& v1, const Vector3& v2)
00369 {
00370         return Vector3(v1.m_floats[0] - v2.m_floats[0], v1.m_floats[1] - v2.m_floats[1], v1.m_floats[2] - v2.m_floats[2]);
00371 }
00373 TF2SIMD_FORCE_INLINE Vector3 
00374 operator-(const Vector3& v)
00375 {
00376         return Vector3(-v.m_floats[0], -v.m_floats[1], -v.m_floats[2]);
00377 }
00378 
00380 TF2SIMD_FORCE_INLINE Vector3 
00381 operator*(const Vector3& v, const tf2Scalar& s)
00382 {
00383         return Vector3(v.m_floats[0] * s, v.m_floats[1] * s, v.m_floats[2] * s);
00384 }
00385 
00387 TF2SIMD_FORCE_INLINE Vector3 
00388 operator*(const tf2Scalar& s, const Vector3& v)
00389 { 
00390         return v * s; 
00391 }
00392 
00394 TF2SIMD_FORCE_INLINE Vector3
00395 operator/(const Vector3& v, const tf2Scalar& s)
00396 {
00397         tf2FullAssert(s != tf2Scalar(0.0));
00398         return v * (tf2Scalar(1.0) / s);
00399 }
00400 
00402 TF2SIMD_FORCE_INLINE Vector3
00403 operator/(const Vector3& v1, const Vector3& v2)
00404 {
00405         return Vector3(v1.m_floats[0] / v2.m_floats[0],v1.m_floats[1] / v2.m_floats[1],v1.m_floats[2] / v2.m_floats[2]);
00406 }
00407 
00409 TF2SIMD_FORCE_INLINE tf2Scalar 
00410 tf2Dot(const Vector3& v1, const Vector3& v2) 
00411 { 
00412         return v1.dot(v2); 
00413 }
00414 
00415 
00417 TF2SIMD_FORCE_INLINE tf2Scalar
00418 tf2Distance2(const Vector3& v1, const Vector3& v2) 
00419 { 
00420         return v1.distance2(v2); 
00421 }
00422 
00423 
00425 TF2SIMD_FORCE_INLINE tf2Scalar
00426 tf2Distance(const Vector3& v1, const Vector3& v2) 
00427 { 
00428         return v1.distance(v2); 
00429 }
00430 
00432 TF2SIMD_FORCE_INLINE tf2Scalar
00433 tf2Angle(const Vector3& v1, const Vector3& v2) 
00434 { 
00435         return v1.angle(v2); 
00436 }
00437 
00439 TF2SIMD_FORCE_INLINE Vector3 
00440 tf2Cross(const Vector3& v1, const Vector3& v2) 
00441 { 
00442         return v1.cross(v2); 
00443 }
00444 
00445 TF2SIMD_FORCE_INLINE tf2Scalar
00446 tf2Triple(const Vector3& v1, const Vector3& v2, const Vector3& v3)
00447 {
00448         return v1.triple(v2, v3);
00449 }
00450 
00455 TF2SIMD_FORCE_INLINE Vector3 
00456 lerp(const Vector3& v1, const Vector3& v2, const tf2Scalar& t)
00457 {
00458         return v1.lerp(v2, t);
00459 }
00460 
00461 
00462 
00463 TF2SIMD_FORCE_INLINE tf2Scalar Vector3::distance2(const Vector3& v) const
00464 {
00465         return (v - *this).length2();
00466 }
00467 
00468 TF2SIMD_FORCE_INLINE tf2Scalar Vector3::distance(const Vector3& v) const
00469 {
00470         return (v - *this).length();
00471 }
00472 
00473 TF2SIMD_FORCE_INLINE Vector3 Vector3::normalized() const
00474 {
00475         return *this / length();
00476 } 
00477 
00478 TF2SIMD_FORCE_INLINE Vector3 Vector3::rotate( const Vector3& wAxis, const tf2Scalar angle ) const
00479 {
00480         // wAxis must be a unit lenght vector
00481 
00482         Vector3 o = wAxis * wAxis.dot( *this );
00483         Vector3 x = *this - o;
00484         Vector3 y;
00485 
00486         y = wAxis.cross( *this );
00487 
00488         return ( o + x * tf2Cos( angle ) + y * tf2Sin( angle ) );
00489 }
00490 
00491 class tf2Vector4 : public Vector3
00492 {
00493 public:
00494 
00495         TF2SIMD_FORCE_INLINE tf2Vector4() {}
00496 
00497 
00498         TF2SIMD_FORCE_INLINE tf2Vector4(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z,const tf2Scalar& w) 
00499                 : Vector3(x,y,z)
00500         {
00501                 m_floats[3] = w;
00502         }
00503 
00504 
00505         TF2SIMD_FORCE_INLINE tf2Vector4 absolute4() const 
00506         {
00507                 return tf2Vector4(
00508                         tf2Fabs(m_floats[0]), 
00509                         tf2Fabs(m_floats[1]), 
00510                         tf2Fabs(m_floats[2]),
00511                         tf2Fabs(m_floats[3]));
00512         }
00513 
00514 
00515 
00516         tf2Scalar       getW() const { return m_floats[3];}
00517 
00518 
00519                 TF2SIMD_FORCE_INLINE int maxAxis4() const
00520         {
00521                 int maxIndex = -1;
00522                 tf2Scalar maxVal = tf2Scalar(-TF2_LARGE_FLOAT);
00523                 if (m_floats[0] > maxVal)
00524                 {
00525                         maxIndex = 0;
00526                         maxVal = m_floats[0];
00527                 }
00528                 if (m_floats[1] > maxVal)
00529                 {
00530                         maxIndex = 1;
00531                         maxVal = m_floats[1];
00532                 }
00533                 if (m_floats[2] > maxVal)
00534                 {
00535                         maxIndex = 2;
00536                         maxVal =m_floats[2];
00537                 }
00538                 if (m_floats[3] > maxVal)
00539                 {
00540                         maxIndex = 3;
00541                 }
00542                 
00543                 
00544                 
00545 
00546                 return maxIndex;
00547 
00548         }
00549 
00550 
00551         TF2SIMD_FORCE_INLINE int minAxis4() const
00552         {
00553                 int minIndex = -1;
00554                 tf2Scalar minVal = tf2Scalar(TF2_LARGE_FLOAT);
00555                 if (m_floats[0] < minVal)
00556                 {
00557                         minIndex = 0;
00558                         minVal = m_floats[0];
00559                 }
00560                 if (m_floats[1] < minVal)
00561                 {
00562                         minIndex = 1;
00563                         minVal = m_floats[1];
00564                 }
00565                 if (m_floats[2] < minVal)
00566                 {
00567                         minIndex = 2;
00568                         minVal =m_floats[2];
00569                 }
00570                 if (m_floats[3] < minVal)
00571                 {
00572                         minIndex = 3;
00573                 }
00574                 
00575                 return minIndex;
00576 
00577         }
00578 
00579 
00580         TF2SIMD_FORCE_INLINE int closestAxis4() const 
00581         {
00582                 return absolute4().maxAxis4();
00583         }
00584 
00585         
00586  
00587 
00595 /*              void getValue(tf2Scalar *m) const 
00596                 {
00597                         m[0] = m_floats[0];
00598                         m[1] = m_floats[1];
00599                         m[2] =m_floats[2];
00600                 }
00601 */
00608                 TF2SIMD_FORCE_INLINE void       setValue(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z,const tf2Scalar& w)
00609                 {
00610                         m_floats[0]=x;
00611                         m_floats[1]=y;
00612                         m_floats[2]=z;
00613                         m_floats[3]=w;
00614                 }
00615 
00616 
00617 };
00618 
00619 
00621 TF2SIMD_FORCE_INLINE void       tf2SwapScalarEndian(const tf2Scalar& sourceVal, tf2Scalar& destVal)
00622 {
00623         unsigned char* dest = (unsigned char*) &destVal;
00624         const unsigned char* src  = (const unsigned char*) &sourceVal;
00625         dest[0] = src[7];
00626     dest[1] = src[6];
00627     dest[2] = src[5];
00628     dest[3] = src[4];
00629     dest[4] = src[3];
00630     dest[5] = src[2];
00631     dest[6] = src[1];
00632     dest[7] = src[0];
00633 }
00635 TF2SIMD_FORCE_INLINE void       tf2SwapVector3Endian(const Vector3& sourceVec, Vector3& destVec)
00636 {
00637         for (int i=0;i<4;i++)
00638         {
00639                 tf2SwapScalarEndian(sourceVec[i],destVec[i]);
00640         }
00641 
00642 }
00643 
00645 TF2SIMD_FORCE_INLINE void       tf2UnSwapVector3Endian(Vector3& vector)
00646 {
00647 
00648         Vector3 swappedVec;
00649         for (int i=0;i<4;i++)
00650         {
00651                 tf2SwapScalarEndian(vector[i],swappedVec[i]);
00652         }
00653         vector = swappedVec;
00654 }
00655 
00656 TF2SIMD_FORCE_INLINE void tf2PlaneSpace1 (const Vector3& n, Vector3& p, Vector3& q)
00657 {
00658   if (tf2Fabs(n.z()) > TF2SIMDSQRT12) {
00659     // choose p in y-z plane
00660     tf2Scalar a = n[1]*n[1] + n[2]*n[2];
00661     tf2Scalar k = tf2RecipSqrt (a);
00662     p.setValue(0,-n[2]*k,n[1]*k);
00663     // set q = n x p
00664     q.setValue(a*k,-n[0]*p[2],n[0]*p[1]);
00665   }
00666   else {
00667     // choose p in x-y plane
00668     tf2Scalar a = n.x()*n.x() + n.y()*n.y();
00669     tf2Scalar k = tf2RecipSqrt (a);
00670     p.setValue(-n.y()*k,n.x()*k,0);
00671     // set q = n x p
00672     q.setValue(-n.z()*p.y(),n.z()*p.x(),a*k);
00673   }
00674 }
00675 
00676 
00677 struct  Vector3FloatData
00678 {
00679         float   m_floats[4];
00680 };
00681 
00682 struct  Vector3DoubleData
00683 {
00684         double  m_floats[4];
00685 
00686 };
00687 
00688 TF2SIMD_FORCE_INLINE    void    Vector3::serializeFloat(struct  Vector3FloatData& dataOut) const
00689 {
00691         for (int i=0;i<4;i++)
00692                 dataOut.m_floats[i] = float(m_floats[i]);
00693 }
00694 
00695 TF2SIMD_FORCE_INLINE void       Vector3::deSerializeFloat(const struct  Vector3FloatData& dataIn)
00696 {
00697         for (int i=0;i<4;i++)
00698                 m_floats[i] = tf2Scalar(dataIn.m_floats[i]);
00699 }
00700 
00701 
00702 TF2SIMD_FORCE_INLINE    void    Vector3::serializeDouble(struct Vector3DoubleData& dataOut) const
00703 {
00705         for (int i=0;i<4;i++)
00706                 dataOut.m_floats[i] = double(m_floats[i]);
00707 }
00708 
00709 TF2SIMD_FORCE_INLINE void       Vector3::deSerializeDouble(const struct Vector3DoubleData& dataIn)
00710 {
00711         for (int i=0;i<4;i++)
00712                 m_floats[i] = tf2Scalar(dataIn.m_floats[i]);
00713 }
00714 
00715 
00716 TF2SIMD_FORCE_INLINE    void    Vector3::serialize(struct       Vector3Data& dataOut) const
00717 {
00719         for (int i=0;i<4;i++)
00720                 dataOut.m_floats[i] = m_floats[i];
00721 }
00722 
00723 TF2SIMD_FORCE_INLINE void       Vector3::deSerialize(const struct       Vector3Data& dataIn)
00724 {
00725         for (int i=0;i<4;i++)
00726                 m_floats[i] = dataIn.m_floats[i];
00727 }
00728 
00729 }
00730 
00731 #endif //TF2_VECTOR3_H


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