00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #ifndef TF_VECTOR3_H
00018 #define TF_VECTOR3_H
00019
00020
00021 #include "Scalar.h"
00022 #include "MinMax.h"
00023
00024 #include "LinearMath/btVector3.h"
00025
00026 namespace tf{
00027
00028 #define Vector3Data Vector3DoubleData
00029 #define Vector3DataName "Vector3DoubleData"
00030
00031
00032
00033
00038 ATTRIBUTE_ALIGNED16(class) Vector3
00039 {
00040 public:
00041
00042 #if defined (__SPU__) && defined (__CELLOS_LV2__)
00043 tfScalar m_floats[4];
00044 public:
00045 TFSIMD_FORCE_INLINE const vec_float4& get128() const
00046 {
00047 return *((const vec_float4*)&m_floats[0]);
00048 }
00049 public:
00050 #else //__CELLOS_LV2__ __SPU__
00051 #ifdef TF_USE_SSE // _WIN32
00052 union {
00053 __m128 mVec128;
00054 tfScalar m_floats[4];
00055 };
00056 TFSIMD_FORCE_INLINE __m128 get128() const
00057 {
00058 return mVec128;
00059 }
00060 TFSIMD_FORCE_INLINE void set128(__m128 v128)
00061 {
00062 mVec128 = v128;
00063 }
00064 #else
00065 tfScalar m_floats[4];
00066 #endif
00067 #endif //__CELLOS_LV2__ __SPU__
00068
00069 public:
00070
00072 TFSIMD_FORCE_INLINE Vector3() {}
00073
00075 TFSIMD_FORCE_INLINE Vector3(const btVector3& other)
00076 {
00077 m_floats[0] = other.m_floats[0];
00078 m_floats[1] = other.m_floats[1];
00079 m_floats[2] = other.m_floats[2];
00080 m_floats[3] = other.m_floats[3];
00081 }
00082
00083
00085 TFSIMD_FORCE_INLINE Vector3& operator=(const btVector3& other)
00086 {
00087 m_floats[0] = other.m_floats[0];
00088 m_floats[1] = other.m_floats[1];
00089 m_floats[2] = other.m_floats[2];
00090 m_floats[3] = other.m_floats[3];
00091 return *this;
00092 }
00093
00099 TFSIMD_FORCE_INLINE Vector3(const tfScalar& x, const tfScalar& y, const tfScalar& z)
00100 {
00101 m_floats[0] = x;
00102 m_floats[1] = y;
00103 m_floats[2] = z;
00104 m_floats[3] = tfScalar(0.);
00105 }
00106
00108 TFSIMD_FORCE_INLINE btVector3 as_bt(void) const __attribute__((deprecated)) { return asBt(); } ;
00109 TFSIMD_FORCE_INLINE btVector3 asBt(void) const
00110 {
00111 return btVector3(m_floats[0], m_floats[1], m_floats[2]);
00112 }
00115 TFSIMD_FORCE_INLINE Vector3& operator+=(const Vector3& v)
00116 {
00117
00118 m_floats[0] += v.m_floats[0]; m_floats[1] += v.m_floats[1];m_floats[2] += v.m_floats[2];
00119 return *this;
00120 }
00121
00122
00125 TFSIMD_FORCE_INLINE Vector3& operator-=(const Vector3& v)
00126 {
00127 m_floats[0] -= v.m_floats[0]; m_floats[1] -= v.m_floats[1];m_floats[2] -= v.m_floats[2];
00128 return *this;
00129 }
00132 TFSIMD_FORCE_INLINE Vector3& operator*=(const tfScalar& s)
00133 {
00134 m_floats[0] *= s; m_floats[1] *= s;m_floats[2] *= s;
00135 return *this;
00136 }
00137
00140 TFSIMD_FORCE_INLINE Vector3& operator/=(const tfScalar& s)
00141 {
00142 tfFullAssert(s != tfScalar(0.0));
00143 return *this *= tfScalar(1.0) / s;
00144 }
00145
00148 TFSIMD_FORCE_INLINE tfScalar dot(const Vector3& v) const
00149 {
00150 return m_floats[0] * v.m_floats[0] + m_floats[1] * v.m_floats[1] +m_floats[2] * v.m_floats[2];
00151 }
00152
00154 TFSIMD_FORCE_INLINE tfScalar length2() const
00155 {
00156 return dot(*this);
00157 }
00158
00160 TFSIMD_FORCE_INLINE tfScalar length() const
00161 {
00162 return tfSqrt(length2());
00163 }
00164
00167 TFSIMD_FORCE_INLINE tfScalar distance2(const Vector3& v) const;
00168
00171 TFSIMD_FORCE_INLINE tfScalar distance(const Vector3& v) const;
00172
00175 TFSIMD_FORCE_INLINE Vector3& normalize()
00176 {
00177 return *this /= length();
00178 }
00179
00181 TFSIMD_FORCE_INLINE Vector3 normalized() const;
00182
00186 TFSIMD_FORCE_INLINE Vector3 rotate( const Vector3& wAxis, const tfScalar angle );
00187
00190 TFSIMD_FORCE_INLINE tfScalar angle(const Vector3& v) const
00191 {
00192 tfScalar s = tfSqrt(length2() * v.length2());
00193 tfFullAssert(s != tfScalar(0.0));
00194 return tfAcos(dot(v) / s);
00195 }
00197 TFSIMD_FORCE_INLINE Vector3 absolute() const
00198 {
00199 return Vector3(
00200 tfFabs(m_floats[0]),
00201 tfFabs(m_floats[1]),
00202 tfFabs(m_floats[2]));
00203 }
00206 TFSIMD_FORCE_INLINE Vector3 cross(const Vector3& v) const
00207 {
00208 return Vector3(
00209 m_floats[1] * v.m_floats[2] -m_floats[2] * v.m_floats[1],
00210 m_floats[2] * v.m_floats[0] - m_floats[0] * v.m_floats[2],
00211 m_floats[0] * v.m_floats[1] - m_floats[1] * v.m_floats[0]);
00212 }
00213
00214 TFSIMD_FORCE_INLINE tfScalar triple(const Vector3& v1, const Vector3& v2) const
00215 {
00216 return m_floats[0] * (v1.m_floats[1] * v2.m_floats[2] - v1.m_floats[2] * v2.m_floats[1]) +
00217 m_floats[1] * (v1.m_floats[2] * v2.m_floats[0] - v1.m_floats[0] * v2.m_floats[2]) +
00218 m_floats[2] * (v1.m_floats[0] * v2.m_floats[1] - v1.m_floats[1] * v2.m_floats[0]);
00219 }
00220
00223 TFSIMD_FORCE_INLINE int minAxis() const
00224 {
00225 return m_floats[0] < m_floats[1] ? (m_floats[0] <m_floats[2] ? 0 : 2) : (m_floats[1] <m_floats[2] ? 1 : 2);
00226 }
00227
00230 TFSIMD_FORCE_INLINE int maxAxis() const
00231 {
00232 return m_floats[0] < m_floats[1] ? (m_floats[1] <m_floats[2] ? 2 : 1) : (m_floats[0] <m_floats[2] ? 2 : 0);
00233 }
00234
00235 TFSIMD_FORCE_INLINE int furthestAxis() const
00236 {
00237 return absolute().minAxis();
00238 }
00239
00240 TFSIMD_FORCE_INLINE int closestAxis() const
00241 {
00242 return absolute().maxAxis();
00243 }
00244
00245 TFSIMD_FORCE_INLINE void setInterpolate3(const Vector3& v0, const Vector3& v1, tfScalar rt)
00246 {
00247 tfScalar s = tfScalar(1.0) - rt;
00248 m_floats[0] = s * v0.m_floats[0] + rt * v1.m_floats[0];
00249 m_floats[1] = s * v0.m_floats[1] + rt * v1.m_floats[1];
00250 m_floats[2] = s * v0.m_floats[2] + rt * v1.m_floats[2];
00251
00252
00253 }
00254
00258 TFSIMD_FORCE_INLINE Vector3 lerp(const Vector3& v, const tfScalar& t) const
00259 {
00260 return Vector3(m_floats[0] + (v.m_floats[0] - m_floats[0]) * t,
00261 m_floats[1] + (v.m_floats[1] - m_floats[1]) * t,
00262 m_floats[2] + (v.m_floats[2] -m_floats[2]) * t);
00263 }
00264
00267 TFSIMD_FORCE_INLINE Vector3& operator*=(const Vector3& v)
00268 {
00269 m_floats[0] *= v.m_floats[0]; m_floats[1] *= v.m_floats[1];m_floats[2] *= v.m_floats[2];
00270 return *this;
00271 }
00272
00274 TFSIMD_FORCE_INLINE const tfScalar& getX() const { return m_floats[0]; }
00276 TFSIMD_FORCE_INLINE const tfScalar& getY() const { return m_floats[1]; }
00278 TFSIMD_FORCE_INLINE const tfScalar& getZ() const { return m_floats[2]; }
00280 TFSIMD_FORCE_INLINE void setX(tfScalar x) { m_floats[0] = x;};
00282 TFSIMD_FORCE_INLINE void setY(tfScalar y) { m_floats[1] = y;};
00284 TFSIMD_FORCE_INLINE void setZ(tfScalar z) {m_floats[2] = z;};
00286 TFSIMD_FORCE_INLINE void setW(tfScalar w) { m_floats[3] = w;};
00288 TFSIMD_FORCE_INLINE const tfScalar& x() const { return m_floats[0]; }
00290 TFSIMD_FORCE_INLINE const tfScalar& y() const { return m_floats[1]; }
00292 TFSIMD_FORCE_INLINE const tfScalar& z() const { return m_floats[2]; }
00294 TFSIMD_FORCE_INLINE const tfScalar& w() const { return m_floats[3]; }
00295
00296
00297
00299 TFSIMD_FORCE_INLINE operator tfScalar *() { return &m_floats[0]; }
00300 TFSIMD_FORCE_INLINE operator const tfScalar *() const { return &m_floats[0]; }
00301
00302 TFSIMD_FORCE_INLINE bool operator==(const Vector3& other) const
00303 {
00304 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]));
00305 }
00306
00307 TFSIMD_FORCE_INLINE bool operator!=(const Vector3& other) const
00308 {
00309 return !(*this == other);
00310 }
00311
00315 TFSIMD_FORCE_INLINE void setMax(const Vector3& other)
00316 {
00317 tfSetMax(m_floats[0], other.m_floats[0]);
00318 tfSetMax(m_floats[1], other.m_floats[1]);
00319 tfSetMax(m_floats[2], other.m_floats[2]);
00320 tfSetMax(m_floats[3], other.w());
00321 }
00325 TFSIMD_FORCE_INLINE void setMin(const Vector3& other)
00326 {
00327 tfSetMin(m_floats[0], other.m_floats[0]);
00328 tfSetMin(m_floats[1], other.m_floats[1]);
00329 tfSetMin(m_floats[2], other.m_floats[2]);
00330 tfSetMin(m_floats[3], other.w());
00331 }
00332
00333 TFSIMD_FORCE_INLINE void setValue(const tfScalar& x, const tfScalar& y, const tfScalar& z)
00334 {
00335 m_floats[0]=x;
00336 m_floats[1]=y;
00337 m_floats[2]=z;
00338 m_floats[3] = tfScalar(0.);
00339 }
00340
00341 void getSkewSymmetricMatrix(Vector3* v0,Vector3* v1,Vector3* v2) const
00342 {
00343 v0->setValue(0. ,-z() ,y());
00344 v1->setValue(z() ,0. ,-x());
00345 v2->setValue(-y() ,x() ,0.);
00346 }
00347
00348 void setZero()
00349 {
00350 setValue(tfScalar(0.),tfScalar(0.),tfScalar(0.));
00351 }
00352
00353 TFSIMD_FORCE_INLINE bool isZero() const
00354 {
00355 return m_floats[0] == tfScalar(0) && m_floats[1] == tfScalar(0) && m_floats[2] == tfScalar(0);
00356 }
00357
00358 TFSIMD_FORCE_INLINE bool fuzzyZero() const
00359 {
00360 return length2() < TFSIMD_EPSILON;
00361 }
00362
00363 TFSIMD_FORCE_INLINE void serialize(struct Vector3Data& dataOut) const;
00364
00365 TFSIMD_FORCE_INLINE void deSerialize(const struct Vector3Data& dataIn);
00366
00367 TFSIMD_FORCE_INLINE void serializeFloat(struct Vector3FloatData& dataOut) const;
00368
00369 TFSIMD_FORCE_INLINE void deSerializeFloat(const struct Vector3FloatData& dataIn);
00370
00371 TFSIMD_FORCE_INLINE void serializeDouble(struct Vector3DoubleData& dataOut) const;
00372
00373 TFSIMD_FORCE_INLINE void deSerializeDouble(const struct Vector3DoubleData& dataIn);
00374
00375 };
00376
00378 TFSIMD_FORCE_INLINE Vector3
00379 operator+(const Vector3& v1, const Vector3& v2)
00380 {
00381 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]);
00382 }
00383
00385 TFSIMD_FORCE_INLINE Vector3
00386 operator*(const Vector3& v1, const Vector3& v2)
00387 {
00388 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]);
00389 }
00390
00392 TFSIMD_FORCE_INLINE Vector3
00393 operator-(const Vector3& v1, const Vector3& v2)
00394 {
00395 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]);
00396 }
00398 TFSIMD_FORCE_INLINE Vector3
00399 operator-(const Vector3& v)
00400 {
00401 return Vector3(-v.m_floats[0], -v.m_floats[1], -v.m_floats[2]);
00402 }
00403
00405 TFSIMD_FORCE_INLINE Vector3
00406 operator*(const Vector3& v, const tfScalar& s)
00407 {
00408 return Vector3(v.m_floats[0] * s, v.m_floats[1] * s, v.m_floats[2] * s);
00409 }
00410
00412 TFSIMD_FORCE_INLINE Vector3
00413 operator*(const tfScalar& s, const Vector3& v)
00414 {
00415 return v * s;
00416 }
00417
00419 TFSIMD_FORCE_INLINE Vector3
00420 operator/(const Vector3& v, const tfScalar& s)
00421 {
00422 tfFullAssert(s != tfScalar(0.0));
00423 return v * (tfScalar(1.0) / s);
00424 }
00425
00427 TFSIMD_FORCE_INLINE Vector3
00428 operator/(const Vector3& v1, const Vector3& v2)
00429 {
00430 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]);
00431 }
00432
00434 TFSIMD_FORCE_INLINE tfScalar
00435 tfDot(const Vector3& v1, const Vector3& v2)
00436 {
00437 return v1.dot(v2);
00438 }
00439
00440
00442 TFSIMD_FORCE_INLINE tfScalar
00443 tfDistance2(const Vector3& v1, const Vector3& v2)
00444 {
00445 return v1.distance2(v2);
00446 }
00447
00448
00450 TFSIMD_FORCE_INLINE tfScalar
00451 tfDistance(const Vector3& v1, const Vector3& v2)
00452 {
00453 return v1.distance(v2);
00454 }
00455
00457 TFSIMD_FORCE_INLINE tfScalar
00458 tfAngle(const Vector3& v1, const Vector3& v2)
00459 {
00460 return v1.angle(v2);
00461 }
00462
00464 TFSIMD_FORCE_INLINE Vector3
00465 tfCross(const Vector3& v1, const Vector3& v2)
00466 {
00467 return v1.cross(v2);
00468 }
00469
00470 TFSIMD_FORCE_INLINE tfScalar
00471 tfTriple(const Vector3& v1, const Vector3& v2, const Vector3& v3)
00472 {
00473 return v1.triple(v2, v3);
00474 }
00475
00480 TFSIMD_FORCE_INLINE Vector3
00481 lerp(const Vector3& v1, const Vector3& v2, const tfScalar& t)
00482 {
00483 return v1.lerp(v2, t);
00484 }
00485
00486
00487
00488 TFSIMD_FORCE_INLINE tfScalar Vector3::distance2(const Vector3& v) const
00489 {
00490 return (v - *this).length2();
00491 }
00492
00493 TFSIMD_FORCE_INLINE tfScalar Vector3::distance(const Vector3& v) const
00494 {
00495 return (v - *this).length();
00496 }
00497
00498 TFSIMD_FORCE_INLINE Vector3 Vector3::normalized() const
00499 {
00500 return *this / length();
00501 }
00502
00503 TFSIMD_FORCE_INLINE Vector3 Vector3::rotate( const Vector3& wAxis, const tfScalar angle )
00504 {
00505
00506
00507 Vector3 o = wAxis * wAxis.dot( *this );
00508 Vector3 x = *this - o;
00509 Vector3 y;
00510
00511 y = wAxis.cross( *this );
00512
00513 return ( o + x * tfCos( angle ) + y * tfSin( angle ) );
00514 }
00515
00516 class tfVector4 : public Vector3
00517 {
00518 public:
00519
00520 TFSIMD_FORCE_INLINE tfVector4() {}
00521
00522
00523 TFSIMD_FORCE_INLINE tfVector4(const tfScalar& x, const tfScalar& y, const tfScalar& z,const tfScalar& w)
00524 : Vector3(x,y,z)
00525 {
00526 m_floats[3] = w;
00527 }
00528
00529
00530 TFSIMD_FORCE_INLINE tfVector4 absolute4() const
00531 {
00532 return tfVector4(
00533 tfFabs(m_floats[0]),
00534 tfFabs(m_floats[1]),
00535 tfFabs(m_floats[2]),
00536 tfFabs(m_floats[3]));
00537 }
00538
00539
00540
00541 tfScalar getW() const { return m_floats[3];}
00542
00543
00544 TFSIMD_FORCE_INLINE int maxAxis4() const
00545 {
00546 int maxIndex = -1;
00547 tfScalar maxVal = tfScalar(-TF_LARGE_FLOAT);
00548 if (m_floats[0] > maxVal)
00549 {
00550 maxIndex = 0;
00551 maxVal = m_floats[0];
00552 }
00553 if (m_floats[1] > maxVal)
00554 {
00555 maxIndex = 1;
00556 maxVal = m_floats[1];
00557 }
00558 if (m_floats[2] > maxVal)
00559 {
00560 maxIndex = 2;
00561 maxVal =m_floats[2];
00562 }
00563 if (m_floats[3] > maxVal)
00564 {
00565 maxIndex = 3;
00566 maxVal = m_floats[3];
00567 }
00568
00569
00570
00571
00572 return maxIndex;
00573
00574 }
00575
00576
00577 TFSIMD_FORCE_INLINE int minAxis4() const
00578 {
00579 int minIndex = -1;
00580 tfScalar minVal = tfScalar(TF_LARGE_FLOAT);
00581 if (m_floats[0] < minVal)
00582 {
00583 minIndex = 0;
00584 minVal = m_floats[0];
00585 }
00586 if (m_floats[1] < minVal)
00587 {
00588 minIndex = 1;
00589 minVal = m_floats[1];
00590 }
00591 if (m_floats[2] < minVal)
00592 {
00593 minIndex = 2;
00594 minVal =m_floats[2];
00595 }
00596 if (m_floats[3] < minVal)
00597 {
00598 minIndex = 3;
00599 minVal = m_floats[3];
00600 }
00601
00602 return minIndex;
00603
00604 }
00605
00606
00607 TFSIMD_FORCE_INLINE int closestAxis4() const
00608 {
00609 return absolute4().maxAxis4();
00610 }
00611
00612
00613
00614
00622
00623
00624
00625
00626
00627
00628
00635 TFSIMD_FORCE_INLINE void setValue(const tfScalar& x, const tfScalar& y, const tfScalar& z,const tfScalar& w)
00636 {
00637 m_floats[0]=x;
00638 m_floats[1]=y;
00639 m_floats[2]=z;
00640 m_floats[3]=w;
00641 }
00642
00643
00644 };
00645
00646
00648 TFSIMD_FORCE_INLINE void tfSwapScalarEndian(const tfScalar& sourceVal, tfScalar& destVal)
00649 {
00650 unsigned char* dest = (unsigned char*) &destVal;
00651 unsigned char* src = (unsigned char*) &sourceVal;
00652 dest[0] = src[7];
00653 dest[1] = src[6];
00654 dest[2] = src[5];
00655 dest[3] = src[4];
00656 dest[4] = src[3];
00657 dest[5] = src[2];
00658 dest[6] = src[1];
00659 dest[7] = src[0];
00660 }
00662 TFSIMD_FORCE_INLINE void tfSwapVector3Endian(const Vector3& sourceVec, Vector3& destVec)
00663 {
00664 for (int i=0;i<4;i++)
00665 {
00666 tfSwapScalarEndian(sourceVec[i],destVec[i]);
00667 }
00668
00669 }
00670
00672 TFSIMD_FORCE_INLINE void tfUnSwapVector3Endian(Vector3& vector)
00673 {
00674
00675 Vector3 swappedVec;
00676 for (int i=0;i<4;i++)
00677 {
00678 tfSwapScalarEndian(vector[i],swappedVec[i]);
00679 }
00680 vector = swappedVec;
00681 }
00682
00683 TFSIMD_FORCE_INLINE void tfPlaneSpace1 (const Vector3& n, Vector3& p, Vector3& q)
00684 {
00685 if (tfFabs(n.z()) > TFSIMDSQRT12) {
00686
00687 tfScalar a = n[1]*n[1] + n[2]*n[2];
00688 tfScalar k = tfRecipSqrt (a);
00689 p.setValue(0,-n[2]*k,n[1]*k);
00690
00691 q.setValue(a*k,-n[0]*p[2],n[0]*p[1]);
00692 }
00693 else {
00694
00695 tfScalar a = n.x()*n.x() + n.y()*n.y();
00696 tfScalar k = tfRecipSqrt (a);
00697 p.setValue(-n.y()*k,n.x()*k,0);
00698
00699 q.setValue(-n.z()*p.y(),n.z()*p.x(),a*k);
00700 }
00701 }
00702
00703
00704 struct Vector3FloatData
00705 {
00706 float m_floats[4];
00707 };
00708
00709 struct Vector3DoubleData
00710 {
00711 double m_floats[4];
00712
00713 };
00714
00715 TFSIMD_FORCE_INLINE void Vector3::serializeFloat(struct Vector3FloatData& dataOut) const
00716 {
00718 for (int i=0;i<4;i++)
00719 dataOut.m_floats[i] = float(m_floats[i]);
00720 }
00721
00722 TFSIMD_FORCE_INLINE void Vector3::deSerializeFloat(const struct Vector3FloatData& dataIn)
00723 {
00724 for (int i=0;i<4;i++)
00725 m_floats[i] = tfScalar(dataIn.m_floats[i]);
00726 }
00727
00728
00729 TFSIMD_FORCE_INLINE void Vector3::serializeDouble(struct Vector3DoubleData& dataOut) const
00730 {
00732 for (int i=0;i<4;i++)
00733 dataOut.m_floats[i] = double(m_floats[i]);
00734 }
00735
00736 TFSIMD_FORCE_INLINE void Vector3::deSerializeDouble(const struct Vector3DoubleData& dataIn)
00737 {
00738 for (int i=0;i<4;i++)
00739 m_floats[i] = tfScalar(dataIn.m_floats[i]);
00740 }
00741
00742
00743 TFSIMD_FORCE_INLINE void Vector3::serialize(struct Vector3Data& dataOut) const
00744 {
00746 for (int i=0;i<4;i++)
00747 dataOut.m_floats[i] = m_floats[i];
00748 }
00749
00750 TFSIMD_FORCE_INLINE void Vector3::deSerialize(const struct Vector3Data& dataIn)
00751 {
00752 for (int i=0;i<4;i++)
00753 m_floats[i] = dataIn.m_floats[i];
00754 }
00755
00756 }
00757
00758 #endif //TFSIMD__VECTOR3_H