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 namespace tf{
00025
00026 #define Vector3Data Vector3DoubleData
00027 #define Vector3DataName "Vector3DoubleData"
00028
00029
00030
00031
00036 ATTRIBUTE_ALIGNED16(class) Vector3
00037 {
00038 public:
00039
00040 #if defined (__SPU__) && defined (__CELLOS_LV2__)
00041 tfScalar m_floats[4];
00042 public:
00043 TFSIMD_FORCE_INLINE const vec_float4& get128() const
00044 {
00045 return *((const vec_float4*)&m_floats[0]);
00046 }
00047 public:
00048 #else //__CELLOS_LV2__ __SPU__
00049 #ifdef TF_USE_SSE // _WIN32
00050 union {
00051 __m128 mVec128;
00052 tfScalar m_floats[4];
00053 };
00054 TFSIMD_FORCE_INLINE __m128 get128() const
00055 {
00056 return mVec128;
00057 }
00058 TFSIMD_FORCE_INLINE void set128(__m128 v128)
00059 {
00060 mVec128 = v128;
00061 }
00062 #else
00063 tfScalar m_floats[4];
00064 #endif
00065 #endif //__CELLOS_LV2__ __SPU__
00066
00067 public:
00068
00070 TFSIMD_FORCE_INLINE Vector3() {}
00071
00072
00078 TFSIMD_FORCE_INLINE Vector3(const tfScalar& x, const tfScalar& y, const tfScalar& z)
00079 {
00080 m_floats[0] = x;
00081 m_floats[1] = y;
00082 m_floats[2] = z;
00083 m_floats[3] = tfScalar(0.);
00084 }
00085
00088 TFSIMD_FORCE_INLINE Vector3& operator+=(const Vector3& v)
00089 {
00090
00091 m_floats[0] += v.m_floats[0]; m_floats[1] += v.m_floats[1];m_floats[2] += v.m_floats[2];
00092 return *this;
00093 }
00094
00095
00098 TFSIMD_FORCE_INLINE Vector3& operator-=(const Vector3& v)
00099 {
00100 m_floats[0] -= v.m_floats[0]; m_floats[1] -= v.m_floats[1];m_floats[2] -= v.m_floats[2];
00101 return *this;
00102 }
00105 TFSIMD_FORCE_INLINE Vector3& operator*=(const tfScalar& s)
00106 {
00107 m_floats[0] *= s; m_floats[1] *= s;m_floats[2] *= s;
00108 return *this;
00109 }
00110
00113 TFSIMD_FORCE_INLINE Vector3& operator/=(const tfScalar& s)
00114 {
00115 tfFullAssert(s != tfScalar(0.0));
00116 return *this *= tfScalar(1.0) / s;
00117 }
00118
00121 TFSIMD_FORCE_INLINE tfScalar dot(const Vector3& v) const
00122 {
00123 return m_floats[0] * v.m_floats[0] + m_floats[1] * v.m_floats[1] +m_floats[2] * v.m_floats[2];
00124 }
00125
00127 TFSIMD_FORCE_INLINE tfScalar length2() const
00128 {
00129 return dot(*this);
00130 }
00131
00133 TFSIMD_FORCE_INLINE tfScalar length() const
00134 {
00135 return tfSqrt(length2());
00136 }
00137
00140 TFSIMD_FORCE_INLINE tfScalar distance2(const Vector3& v) const;
00141
00144 TFSIMD_FORCE_INLINE tfScalar distance(const Vector3& v) const;
00145
00148 TFSIMD_FORCE_INLINE Vector3& normalize()
00149 {
00150 return *this /= length();
00151 }
00152
00154 TFSIMD_FORCE_INLINE Vector3 normalized() const;
00155
00159 TFSIMD_FORCE_INLINE Vector3 rotate( const Vector3& wAxis, const tfScalar angle );
00160
00163 TFSIMD_FORCE_INLINE tfScalar angle(const Vector3& v) const
00164 {
00165 tfScalar s = tfSqrt(length2() * v.length2());
00166 tfFullAssert(s != tfScalar(0.0));
00167 return tfAcos(dot(v) / s);
00168 }
00170 TFSIMD_FORCE_INLINE Vector3 absolute() const
00171 {
00172 return Vector3(
00173 tfFabs(m_floats[0]),
00174 tfFabs(m_floats[1]),
00175 tfFabs(m_floats[2]));
00176 }
00179 TFSIMD_FORCE_INLINE Vector3 cross(const Vector3& v) const
00180 {
00181 return Vector3(
00182 m_floats[1] * v.m_floats[2] -m_floats[2] * v.m_floats[1],
00183 m_floats[2] * v.m_floats[0] - m_floats[0] * v.m_floats[2],
00184 m_floats[0] * v.m_floats[1] - m_floats[1] * v.m_floats[0]);
00185 }
00186
00187 TFSIMD_FORCE_INLINE tfScalar triple(const Vector3& v1, const Vector3& v2) const
00188 {
00189 return m_floats[0] * (v1.m_floats[1] * v2.m_floats[2] - v1.m_floats[2] * v2.m_floats[1]) +
00190 m_floats[1] * (v1.m_floats[2] * v2.m_floats[0] - v1.m_floats[0] * v2.m_floats[2]) +
00191 m_floats[2] * (v1.m_floats[0] * v2.m_floats[1] - v1.m_floats[1] * v2.m_floats[0]);
00192 }
00193
00196 TFSIMD_FORCE_INLINE int minAxis() const
00197 {
00198 return m_floats[0] < m_floats[1] ? (m_floats[0] <m_floats[2] ? 0 : 2) : (m_floats[1] <m_floats[2] ? 1 : 2);
00199 }
00200
00203 TFSIMD_FORCE_INLINE int maxAxis() const
00204 {
00205 return m_floats[0] < m_floats[1] ? (m_floats[1] <m_floats[2] ? 2 : 1) : (m_floats[0] <m_floats[2] ? 2 : 0);
00206 }
00207
00208 TFSIMD_FORCE_INLINE int furthestAxis() const
00209 {
00210 return absolute().minAxis();
00211 }
00212
00213 TFSIMD_FORCE_INLINE int closestAxis() const
00214 {
00215 return absolute().maxAxis();
00216 }
00217
00218 TFSIMD_FORCE_INLINE void setInterpolate3(const Vector3& v0, const Vector3& v1, tfScalar rt)
00219 {
00220 tfScalar s = tfScalar(1.0) - rt;
00221 m_floats[0] = s * v0.m_floats[0] + rt * v1.m_floats[0];
00222 m_floats[1] = s * v0.m_floats[1] + rt * v1.m_floats[1];
00223 m_floats[2] = s * v0.m_floats[2] + rt * v1.m_floats[2];
00224
00225
00226 }
00227
00231 TFSIMD_FORCE_INLINE Vector3 lerp(const Vector3& v, const tfScalar& t) const
00232 {
00233 return Vector3(m_floats[0] + (v.m_floats[0] - m_floats[0]) * t,
00234 m_floats[1] + (v.m_floats[1] - m_floats[1]) * t,
00235 m_floats[2] + (v.m_floats[2] -m_floats[2]) * t);
00236 }
00237
00240 TFSIMD_FORCE_INLINE Vector3& operator*=(const Vector3& v)
00241 {
00242 m_floats[0] *= v.m_floats[0]; m_floats[1] *= v.m_floats[1];m_floats[2] *= v.m_floats[2];
00243 return *this;
00244 }
00245
00247 TFSIMD_FORCE_INLINE const tfScalar& getX() const { return m_floats[0]; }
00249 TFSIMD_FORCE_INLINE const tfScalar& getY() const { return m_floats[1]; }
00251 TFSIMD_FORCE_INLINE const tfScalar& getZ() const { return m_floats[2]; }
00253 TFSIMD_FORCE_INLINE void setX(tfScalar x) { m_floats[0] = x;};
00255 TFSIMD_FORCE_INLINE void setY(tfScalar y) { m_floats[1] = y;};
00257 TFSIMD_FORCE_INLINE void setZ(tfScalar z) {m_floats[2] = z;};
00259 TFSIMD_FORCE_INLINE void setW(tfScalar w) { m_floats[3] = w;};
00261 TFSIMD_FORCE_INLINE const tfScalar& x() const { return m_floats[0]; }
00263 TFSIMD_FORCE_INLINE const tfScalar& y() const { return m_floats[1]; }
00265 TFSIMD_FORCE_INLINE const tfScalar& z() const { return m_floats[2]; }
00267 TFSIMD_FORCE_INLINE const tfScalar& w() const { return m_floats[3]; }
00268
00269
00270
00272 TFSIMD_FORCE_INLINE operator tfScalar *() { return &m_floats[0]; }
00273 TFSIMD_FORCE_INLINE operator const tfScalar *() const { return &m_floats[0]; }
00274
00275 TFSIMD_FORCE_INLINE bool operator==(const Vector3& other) const
00276 {
00277 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]));
00278 }
00279
00280 TFSIMD_FORCE_INLINE bool operator!=(const Vector3& other) const
00281 {
00282 return !(*this == other);
00283 }
00284
00288 TFSIMD_FORCE_INLINE void setMax(const Vector3& other)
00289 {
00290 tfSetMax(m_floats[0], other.m_floats[0]);
00291 tfSetMax(m_floats[1], other.m_floats[1]);
00292 tfSetMax(m_floats[2], other.m_floats[2]);
00293 tfSetMax(m_floats[3], other.w());
00294 }
00298 TFSIMD_FORCE_INLINE void setMin(const Vector3& other)
00299 {
00300 tfSetMin(m_floats[0], other.m_floats[0]);
00301 tfSetMin(m_floats[1], other.m_floats[1]);
00302 tfSetMin(m_floats[2], other.m_floats[2]);
00303 tfSetMin(m_floats[3], other.w());
00304 }
00305
00306 TFSIMD_FORCE_INLINE void setValue(const tfScalar& x, const tfScalar& y, const tfScalar& z)
00307 {
00308 m_floats[0]=x;
00309 m_floats[1]=y;
00310 m_floats[2]=z;
00311 m_floats[3] = tfScalar(0.);
00312 }
00313
00314 void getSkewSymmetricMatrix(Vector3* v0,Vector3* v1,Vector3* v2) const
00315 {
00316 v0->setValue(0. ,-z() ,y());
00317 v1->setValue(z() ,0. ,-x());
00318 v2->setValue(-y() ,x() ,0.);
00319 }
00320
00321 void setZero()
00322 {
00323 setValue(tfScalar(0.),tfScalar(0.),tfScalar(0.));
00324 }
00325
00326 TFSIMD_FORCE_INLINE bool isZero() const
00327 {
00328 return m_floats[0] == tfScalar(0) && m_floats[1] == tfScalar(0) && m_floats[2] == tfScalar(0);
00329 }
00330
00331 TFSIMD_FORCE_INLINE bool fuzzyZero() const
00332 {
00333 return length2() < TFSIMD_EPSILON;
00334 }
00335
00336 TFSIMD_FORCE_INLINE void serialize(struct Vector3Data& dataOut) const;
00337
00338 TFSIMD_FORCE_INLINE void deSerialize(const struct Vector3Data& dataIn);
00339
00340 TFSIMD_FORCE_INLINE void serializeFloat(struct Vector3FloatData& dataOut) const;
00341
00342 TFSIMD_FORCE_INLINE void deSerializeFloat(const struct Vector3FloatData& dataIn);
00343
00344 TFSIMD_FORCE_INLINE void serializeDouble(struct Vector3DoubleData& dataOut) const;
00345
00346 TFSIMD_FORCE_INLINE void deSerializeDouble(const struct Vector3DoubleData& dataIn);
00347
00348 };
00349
00351 TFSIMD_FORCE_INLINE Vector3
00352 operator+(const Vector3& v1, const Vector3& v2)
00353 {
00354 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]);
00355 }
00356
00358 TFSIMD_FORCE_INLINE Vector3
00359 operator*(const Vector3& v1, const Vector3& v2)
00360 {
00361 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]);
00362 }
00363
00365 TFSIMD_FORCE_INLINE Vector3
00366 operator-(const Vector3& v1, const Vector3& v2)
00367 {
00368 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]);
00369 }
00371 TFSIMD_FORCE_INLINE Vector3
00372 operator-(const Vector3& v)
00373 {
00374 return Vector3(-v.m_floats[0], -v.m_floats[1], -v.m_floats[2]);
00375 }
00376
00378 TFSIMD_FORCE_INLINE Vector3
00379 operator*(const Vector3& v, const tfScalar& s)
00380 {
00381 return Vector3(v.m_floats[0] * s, v.m_floats[1] * s, v.m_floats[2] * s);
00382 }
00383
00385 TFSIMD_FORCE_INLINE Vector3
00386 operator*(const tfScalar& s, const Vector3& v)
00387 {
00388 return v * s;
00389 }
00390
00392 TFSIMD_FORCE_INLINE Vector3
00393 operator/(const Vector3& v, const tfScalar& s)
00394 {
00395 tfFullAssert(s != tfScalar(0.0));
00396 return v * (tfScalar(1.0) / s);
00397 }
00398
00400 TFSIMD_FORCE_INLINE Vector3
00401 operator/(const Vector3& v1, const Vector3& v2)
00402 {
00403 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]);
00404 }
00405
00407 TFSIMD_FORCE_INLINE tfScalar
00408 tfDot(const Vector3& v1, const Vector3& v2)
00409 {
00410 return v1.dot(v2);
00411 }
00412
00413
00415 TFSIMD_FORCE_INLINE tfScalar
00416 tfDistance2(const Vector3& v1, const Vector3& v2)
00417 {
00418 return v1.distance2(v2);
00419 }
00420
00421
00423 TFSIMD_FORCE_INLINE tfScalar
00424 tfDistance(const Vector3& v1, const Vector3& v2)
00425 {
00426 return v1.distance(v2);
00427 }
00428
00430 TFSIMD_FORCE_INLINE tfScalar
00431 tfAngle(const Vector3& v1, const Vector3& v2)
00432 {
00433 return v1.angle(v2);
00434 }
00435
00437 TFSIMD_FORCE_INLINE Vector3
00438 tfCross(const Vector3& v1, const Vector3& v2)
00439 {
00440 return v1.cross(v2);
00441 }
00442
00443 TFSIMD_FORCE_INLINE tfScalar
00444 tfTriple(const Vector3& v1, const Vector3& v2, const Vector3& v3)
00445 {
00446 return v1.triple(v2, v3);
00447 }
00448
00453 TFSIMD_FORCE_INLINE Vector3
00454 lerp(const Vector3& v1, const Vector3& v2, const tfScalar& t)
00455 {
00456 return v1.lerp(v2, t);
00457 }
00458
00459
00460
00461 TFSIMD_FORCE_INLINE tfScalar Vector3::distance2(const Vector3& v) const
00462 {
00463 return (v - *this).length2();
00464 }
00465
00466 TFSIMD_FORCE_INLINE tfScalar Vector3::distance(const Vector3& v) const
00467 {
00468 return (v - *this).length();
00469 }
00470
00471 TFSIMD_FORCE_INLINE Vector3 Vector3::normalized() const
00472 {
00473 return *this / length();
00474 }
00475
00476 TFSIMD_FORCE_INLINE Vector3 Vector3::rotate( const Vector3& wAxis, const tfScalar angle )
00477 {
00478
00479
00480 Vector3 o = wAxis * wAxis.dot( *this );
00481 Vector3 x = *this - o;
00482 Vector3 y;
00483
00484 y = wAxis.cross( *this );
00485
00486 return ( o + x * tfCos( angle ) + y * tfSin( angle ) );
00487 }
00488
00489 class tfVector4 : public Vector3
00490 {
00491 public:
00492
00493 TFSIMD_FORCE_INLINE tfVector4() {}
00494
00495
00496 TFSIMD_FORCE_INLINE tfVector4(const tfScalar& x, const tfScalar& y, const tfScalar& z,const tfScalar& w)
00497 : Vector3(x,y,z)
00498 {
00499 m_floats[3] = w;
00500 }
00501
00502
00503 TFSIMD_FORCE_INLINE tfVector4 absolute4() const
00504 {
00505 return tfVector4(
00506 tfFabs(m_floats[0]),
00507 tfFabs(m_floats[1]),
00508 tfFabs(m_floats[2]),
00509 tfFabs(m_floats[3]));
00510 }
00511
00512
00513
00514 tfScalar getW() const { return m_floats[3];}
00515
00516
00517 TFSIMD_FORCE_INLINE int maxAxis4() const
00518 {
00519 int maxIndex = -1;
00520 tfScalar maxVal = tfScalar(-TF_LARGE_FLOAT);
00521 if (m_floats[0] > maxVal)
00522 {
00523 maxIndex = 0;
00524 maxVal = m_floats[0];
00525 }
00526 if (m_floats[1] > maxVal)
00527 {
00528 maxIndex = 1;
00529 maxVal = m_floats[1];
00530 }
00531 if (m_floats[2] > maxVal)
00532 {
00533 maxIndex = 2;
00534 maxVal =m_floats[2];
00535 }
00536 if (m_floats[3] > maxVal)
00537 {
00538 maxIndex = 3;
00539 maxVal = m_floats[3];
00540 }
00541
00542
00543
00544
00545 return maxIndex;
00546
00547 }
00548
00549
00550 TFSIMD_FORCE_INLINE int minAxis4() const
00551 {
00552 int minIndex = -1;
00553 tfScalar minVal = tfScalar(TF_LARGE_FLOAT);
00554 if (m_floats[0] < minVal)
00555 {
00556 minIndex = 0;
00557 minVal = m_floats[0];
00558 }
00559 if (m_floats[1] < minVal)
00560 {
00561 minIndex = 1;
00562 minVal = m_floats[1];
00563 }
00564 if (m_floats[2] < minVal)
00565 {
00566 minIndex = 2;
00567 minVal =m_floats[2];
00568 }
00569 if (m_floats[3] < minVal)
00570 {
00571 minIndex = 3;
00572 minVal = m_floats[3];
00573 }
00574
00575 return minIndex;
00576
00577 }
00578
00579
00580 TFSIMD_FORCE_INLINE int closestAxis4() const
00581 {
00582 return absolute4().maxAxis4();
00583 }
00584
00585
00586
00587
00595
00596
00597
00598
00599
00600
00601
00608 TFSIMD_FORCE_INLINE void setValue(const tfScalar& x, const tfScalar& y, const tfScalar& z,const tfScalar& 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 TFSIMD_FORCE_INLINE void tfSwapScalarEndian(const tfScalar& sourceVal, tfScalar& destVal)
00622 {
00623 unsigned char* dest = (unsigned char*) &destVal;
00624 unsigned char* src = (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 TFSIMD_FORCE_INLINE void tfSwapVector3Endian(const Vector3& sourceVec, Vector3& destVec)
00636 {
00637 for (int i=0;i<4;i++)
00638 {
00639 tfSwapScalarEndian(sourceVec[i],destVec[i]);
00640 }
00641
00642 }
00643
00645 TFSIMD_FORCE_INLINE void tfUnSwapVector3Endian(Vector3& vector)
00646 {
00647
00648 Vector3 swappedVec;
00649 for (int i=0;i<4;i++)
00650 {
00651 tfSwapScalarEndian(vector[i],swappedVec[i]);
00652 }
00653 vector = swappedVec;
00654 }
00655
00656 TFSIMD_FORCE_INLINE void tfPlaneSpace1 (const Vector3& n, Vector3& p, Vector3& q)
00657 {
00658 if (tfFabs(n.z()) > TFSIMDSQRT12) {
00659
00660 tfScalar a = n[1]*n[1] + n[2]*n[2];
00661 tfScalar k = tfRecipSqrt (a);
00662 p.setValue(0,-n[2]*k,n[1]*k);
00663
00664 q.setValue(a*k,-n[0]*p[2],n[0]*p[1]);
00665 }
00666 else {
00667
00668 tfScalar a = n.x()*n.x() + n.y()*n.y();
00669 tfScalar k = tfRecipSqrt (a);
00670 p.setValue(-n.y()*k,n.x()*k,0);
00671
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 TFSIMD_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 TFSIMD_FORCE_INLINE void Vector3::deSerializeFloat(const struct Vector3FloatData& dataIn)
00696 {
00697 for (int i=0;i<4;i++)
00698 m_floats[i] = tfScalar(dataIn.m_floats[i]);
00699 }
00700
00701
00702 TFSIMD_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 TFSIMD_FORCE_INLINE void Vector3::deSerializeDouble(const struct Vector3DoubleData& dataIn)
00710 {
00711 for (int i=0;i<4;i++)
00712 m_floats[i] = tfScalar(dataIn.m_floats[i]);
00713 }
00714
00715
00716 TFSIMD_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 TFSIMD_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 //TFSIMD__VECTOR3_H