Vector3.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/
3 
4 This software is provided 'as-is', without any express or implied warranty.
5 In no event will the authors be held liable for any damages arising from the use of this software.
6 Permission is granted to anyone to use this software for any purpose,
7 including commercial applications, and to alter it and redistribute it freely,
8 subject to the following restrictions:
9 
10 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.
11 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
12 3. This notice may not be removed or altered from any source distribution.
13 */
14 
15 
16 
17 #ifndef TF_VECTOR3_H
18 #define TF_VECTOR3_H
19 
20 
21 #include "Scalar.h"
22 #include "MinMax.h"
23 
24 namespace tf{
25 
26 #define Vector3Data Vector3DoubleData
27 #define Vector3DataName "Vector3DoubleData"
28 
29 
30 
31 
39 {
40 public:
41 
42 #if defined (__SPU__) && defined (__CELLOS_LV2__)
43  tfScalar m_floats[4];
44 public:
45  TFSIMD_FORCE_INLINE const vec_float4& get128() const
46  {
47  return *((const vec_float4*)&m_floats[0]);
48  }
49 public:
50 #else //__CELLOS_LV2__ __SPU__
51 #ifdef TF_USE_SSE // _WIN32
52  union {
53  __m128 mVec128;
54  tfScalar m_floats[4];
55  };
56  TFSIMD_FORCE_INLINE __m128 get128() const
57  {
58  return mVec128;
59  }
60  TFSIMD_FORCE_INLINE void set128(__m128 v128)
61  {
62  mVec128 = v128;
63  }
64 #else
65  tfScalar m_floats[4];
66 #endif
67 #endif //__CELLOS_LV2__ __SPU__
68 
69  public:
70 
73 
74 
80  TFSIMD_FORCE_INLINE Vector3(const tfScalar& x, const tfScalar& y, const tfScalar& z)
81  {
82  m_floats[0] = x;
83  m_floats[1] = y;
84  m_floats[2] = z;
85  m_floats[3] = tfScalar(0.);
86  }
87 
90  TFSIMD_FORCE_INLINE Vector3& operator+=(const Vector3& v)
91  {
92 
93  m_floats[0] += v.m_floats[0]; m_floats[1] += v.m_floats[1];m_floats[2] += v.m_floats[2];
94  return *this;
95  }
96 
97 
100  TFSIMD_FORCE_INLINE Vector3& operator-=(const Vector3& v)
101  {
102  m_floats[0] -= v.m_floats[0]; m_floats[1] -= v.m_floats[1];m_floats[2] -= v.m_floats[2];
103  return *this;
104  }
107  TFSIMD_FORCE_INLINE Vector3& operator*=(const tfScalar& s)
108  {
109  m_floats[0] *= s; m_floats[1] *= s;m_floats[2] *= s;
110  return *this;
111  }
112 
115  TFSIMD_FORCE_INLINE Vector3& operator/=(const tfScalar& s)
116  {
117  tfFullAssert(s != tfScalar(0.0));
118  return *this *= tfScalar(1.0) / s;
119  }
120 
123  TFSIMD_FORCE_INLINE tfScalar dot(const Vector3& v) const
124  {
125  return m_floats[0] * v.m_floats[0] + m_floats[1] * v.m_floats[1] +m_floats[2] * v.m_floats[2];
126  }
127 
129  TFSIMD_FORCE_INLINE tfScalar length2() const
130  {
131  return dot(*this);
132  }
133 
136  {
137  return tfSqrt(length2());
138  }
139 
142  TFSIMD_FORCE_INLINE tfScalar distance2(const Vector3& v) const;
143 
146  TFSIMD_FORCE_INLINE tfScalar distance(const Vector3& v) const;
147 
150  TFSIMD_FORCE_INLINE Vector3& normalize()
151  {
152  return *this /= length();
153  }
154 
156  TFSIMD_FORCE_INLINE Vector3 normalized() const;
157 
161  TFSIMD_FORCE_INLINE Vector3 rotate( const Vector3& wAxis, const tfScalar angle ) const;
162 
165  TFSIMD_FORCE_INLINE tfScalar angle(const Vector3& v) const
166  {
167  tfScalar s = tfSqrt(length2() * v.length2());
168  tfFullAssert(s != tfScalar(0.0));
169  return tfAcos(dot(v) / s);
170  }
172  TFSIMD_FORCE_INLINE Vector3 absolute() const
173  {
174  return Vector3(
175  tfFabs(m_floats[0]),
176  tfFabs(m_floats[1]),
177  tfFabs(m_floats[2]));
178  }
181  TFSIMD_FORCE_INLINE Vector3 cross(const Vector3& v) const
182  {
183  return Vector3(
184  m_floats[1] * v.m_floats[2] -m_floats[2] * v.m_floats[1],
185  m_floats[2] * v.m_floats[0] - m_floats[0] * v.m_floats[2],
186  m_floats[0] * v.m_floats[1] - m_floats[1] * v.m_floats[0]);
187  }
188 
189  TFSIMD_FORCE_INLINE tfScalar triple(const Vector3& v1, const Vector3& v2) const
190  {
191  return m_floats[0] * (v1.m_floats[1] * v2.m_floats[2] - v1.m_floats[2] * v2.m_floats[1]) +
192  m_floats[1] * (v1.m_floats[2] * v2.m_floats[0] - v1.m_floats[0] * v2.m_floats[2]) +
193  m_floats[2] * (v1.m_floats[0] * v2.m_floats[1] - v1.m_floats[1] * v2.m_floats[0]);
194  }
195 
198  TFSIMD_FORCE_INLINE int minAxis() const
199  {
200  return m_floats[0] < m_floats[1] ? (m_floats[0] <m_floats[2] ? 0 : 2) : (m_floats[1] <m_floats[2] ? 1 : 2);
201  }
202 
205  TFSIMD_FORCE_INLINE int maxAxis() const
206  {
207  return m_floats[0] < m_floats[1] ? (m_floats[1] <m_floats[2] ? 2 : 1) : (m_floats[0] <m_floats[2] ? 2 : 0);
208  }
209 
210  TFSIMD_FORCE_INLINE int furthestAxis() const
211  {
212  return absolute().minAxis();
213  }
214 
215  TFSIMD_FORCE_INLINE int closestAxis() const
216  {
217  return absolute().maxAxis();
218  }
219 
220  TFSIMD_FORCE_INLINE void setInterpolate3(const Vector3& v0, const Vector3& v1, tfScalar rt)
221  {
222  tfScalar s = tfScalar(1.0) - rt;
223  m_floats[0] = s * v0.m_floats[0] + rt * v1.m_floats[0];
224  m_floats[1] = s * v0.m_floats[1] + rt * v1.m_floats[1];
225  m_floats[2] = s * v0.m_floats[2] + rt * v1.m_floats[2];
226  //don't do the unused w component
227  // m_co[3] = s * v0[3] + rt * v1[3];
228  }
229 
233  TFSIMD_FORCE_INLINE Vector3 lerp(const Vector3& v, const tfScalar& t) const
234  {
235  return Vector3(m_floats[0] + (v.m_floats[0] - m_floats[0]) * t,
236  m_floats[1] + (v.m_floats[1] - m_floats[1]) * t,
237  m_floats[2] + (v.m_floats[2] -m_floats[2]) * t);
238  }
239 
242  TFSIMD_FORCE_INLINE Vector3& operator*=(const Vector3& v)
243  {
244  m_floats[0] *= v.m_floats[0]; m_floats[1] *= v.m_floats[1];m_floats[2] *= v.m_floats[2];
245  return *this;
246  }
247 
249  TFSIMD_FORCE_INLINE const tfScalar& getX() const { return m_floats[0]; }
251  TFSIMD_FORCE_INLINE const tfScalar& getY() const { return m_floats[1]; }
253  TFSIMD_FORCE_INLINE const tfScalar& getZ() const { return m_floats[2]; }
255  TFSIMD_FORCE_INLINE void setX(tfScalar x) { m_floats[0] = x;};
257  TFSIMD_FORCE_INLINE void setY(tfScalar y) { m_floats[1] = y;};
259  TFSIMD_FORCE_INLINE void setZ(tfScalar z) {m_floats[2] = z;};
261  TFSIMD_FORCE_INLINE void setW(tfScalar w) { m_floats[3] = w;};
263  TFSIMD_FORCE_INLINE const tfScalar& x() const { return m_floats[0]; }
265  TFSIMD_FORCE_INLINE const tfScalar& y() const { return m_floats[1]; }
267  TFSIMD_FORCE_INLINE const tfScalar& z() const { return m_floats[2]; }
269  TFSIMD_FORCE_INLINE const tfScalar& w() const { return m_floats[3]; }
270 
271  //TFSIMD_FORCE_INLINE tfScalar& operator[](int i) { return (&m_floats[0])[i]; }
272  //TFSIMD_FORCE_INLINE const tfScalar& operator[](int i) const { return (&m_floats[0])[i]; }
274  TFSIMD_FORCE_INLINE operator tfScalar *() { return &m_floats[0]; }
275  TFSIMD_FORCE_INLINE operator const tfScalar *() const { return &m_floats[0]; }
276 
277  TFSIMD_FORCE_INLINE bool operator==(const Vector3& other) const
278  {
279  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]));
280  }
281 
282  TFSIMD_FORCE_INLINE bool operator!=(const Vector3& other) const
283  {
284  return !(*this == other);
285  }
286 
290  TFSIMD_FORCE_INLINE void setMax(const Vector3& other)
291  {
292  tfSetMax(m_floats[0], other.m_floats[0]);
293  tfSetMax(m_floats[1], other.m_floats[1]);
294  tfSetMax(m_floats[2], other.m_floats[2]);
295  tfSetMax(m_floats[3], other.w());
296  }
300  TFSIMD_FORCE_INLINE void setMin(const Vector3& other)
301  {
302  tfSetMin(m_floats[0], other.m_floats[0]);
303  tfSetMin(m_floats[1], other.m_floats[1]);
304  tfSetMin(m_floats[2], other.m_floats[2]);
305  tfSetMin(m_floats[3], other.w());
306  }
307 
308  TFSIMD_FORCE_INLINE void setValue(const tfScalar& x, const tfScalar& y, const tfScalar& z)
309  {
310  m_floats[0]=x;
311  m_floats[1]=y;
312  m_floats[2]=z;
313  m_floats[3] = tfScalar(0.);
314  }
315 
316  void getSkewSymmetricMatrix(Vector3* v0,Vector3* v1,Vector3* v2) const
317  {
318  v0->setValue(0. ,-z() ,y());
319  v1->setValue(z() ,0. ,-x());
320  v2->setValue(-y() ,x() ,0.);
321  }
322 
323  void setZero()
324  {
325  setValue(tfScalar(0.),tfScalar(0.),tfScalar(0.));
326  }
327 
328  TFSIMD_FORCE_INLINE bool isZero() const
329  {
330  return m_floats[0] == tfScalar(0) && m_floats[1] == tfScalar(0) && m_floats[2] == tfScalar(0);
331  }
332 
333  TFSIMD_FORCE_INLINE bool fuzzyZero() const
334  {
335  return length2() < TFSIMD_EPSILON;
336  }
337 
338  TFSIMD_FORCE_INLINE void serialize(struct Vector3Data& dataOut) const;
339 
340  TFSIMD_FORCE_INLINE void deSerialize(const struct Vector3Data& dataIn);
341 
342  TFSIMD_FORCE_INLINE void serializeFloat(struct Vector3FloatData& dataOut) const;
343 
344  TFSIMD_FORCE_INLINE void deSerializeFloat(const struct Vector3FloatData& dataIn);
345 
346  TFSIMD_FORCE_INLINE void serializeDouble(struct Vector3DoubleData& dataOut) const;
347 
348  TFSIMD_FORCE_INLINE void deSerializeDouble(const struct Vector3DoubleData& dataIn);
349 
350 };
351 
354 operator+(const Vector3& v1, const Vector3& v2)
355 {
356  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]);
357 }
358 
361 operator*(const Vector3& v1, const Vector3& v2)
362 {
363  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]);
364 }
365 
368 operator-(const Vector3& v1, const Vector3& v2)
369 {
370  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]);
371 }
375 {
376  return Vector3(-v.m_floats[0], -v.m_floats[1], -v.m_floats[2]);
377 }
378 
381 operator*(const Vector3& v, const tfScalar& s)
382 {
383  return Vector3(v.m_floats[0] * s, v.m_floats[1] * s, v.m_floats[2] * s);
384 }
385 
388 operator*(const tfScalar& s, const Vector3& v)
389 {
390  return v * s;
391 }
392 
395 operator/(const Vector3& v, const tfScalar& s)
396 {
397  tfFullAssert(s != tfScalar(0.0));
398  return v * (tfScalar(1.0) / s);
399 }
400 
403 operator/(const Vector3& v1, const Vector3& v2)
404 {
405  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]);
406 }
407 
410 tfDot(const Vector3& v1, const Vector3& v2)
411 {
412  return v1.dot(v2);
413 }
414 
415 
418 tfDistance2(const Vector3& v1, const Vector3& v2)
419 {
420  return v1.distance2(v2);
421 }
422 
423 
426 tfDistance(const Vector3& v1, const Vector3& v2)
427 {
428  return v1.distance(v2);
429 }
430 
433 tfAngle(const Vector3& v1, const Vector3& v2)
434 {
435  return v1.angle(v2);
436 }
437 
440 tfCross(const Vector3& v1, const Vector3& v2)
441 {
442  return v1.cross(v2);
443 }
444 
446 tfTriple(const Vector3& v1, const Vector3& v2, const Vector3& v3)
447 {
448  return v1.triple(v2, v3);
449 }
450 
456 lerp(const Vector3& v1, const Vector3& v2, const tfScalar& t)
457 {
458  return v1.lerp(v2, t);
459 }
460 
461 
462 
463 TFSIMD_FORCE_INLINE tfScalar Vector3::distance2(const Vector3& v) const
464 {
465  return (v - *this).length2();
466 }
467 
468 TFSIMD_FORCE_INLINE tfScalar Vector3::distance(const Vector3& v) const
469 {
470  return (v - *this).length();
471 }
472 
473 TFSIMD_FORCE_INLINE Vector3 Vector3::normalized() const
474 {
475  return *this / length();
476 }
477 
478 TFSIMD_FORCE_INLINE Vector3 Vector3::rotate( const Vector3& wAxis, const tfScalar angle ) const
479 {
480  // wAxis must be a unit lenght vector
481 
482  Vector3 o = wAxis * wAxis.dot( *this );
483  Vector3 x = *this - o;
484  Vector3 y;
485 
486  y = wAxis.cross( *this );
487 
488  return ( o + x * tfCos( angle ) + y * tfSin( angle ) );
489 }
490 
491 class tfVector4 : public Vector3
492 {
493 public:
494 
496 
497 
498  TFSIMD_FORCE_INLINE tfVector4(const tfScalar& x, const tfScalar& y, const tfScalar& z,const tfScalar& w)
499  : Vector3(x,y,z)
500  {
501  m_floats[3] = w;
502  }
503 
504 
506  {
507  return tfVector4(
508  tfFabs(m_floats[0]),
509  tfFabs(m_floats[1]),
510  tfFabs(m_floats[2]),
511  tfFabs(m_floats[3]));
512  }
513 
514 
515 
516  tfScalar getW() const { return m_floats[3];}
517 
518 
520  {
521  int maxIndex = -1;
522  tfScalar maxVal = tfScalar(-TF_LARGE_FLOAT);
523  if (m_floats[0] > maxVal)
524  {
525  maxIndex = 0;
526  maxVal = m_floats[0];
527  }
528  if (m_floats[1] > maxVal)
529  {
530  maxIndex = 1;
531  maxVal = m_floats[1];
532  }
533  if (m_floats[2] > maxVal)
534  {
535  maxIndex = 2;
536  maxVal =m_floats[2];
537  }
538  if (m_floats[3] > maxVal)
539  {
540  maxIndex = 3;
541  maxVal = m_floats[3];
542  }
543 
544 
545 
546 
547  return maxIndex;
548 
549  }
550 
551 
553  {
554  int minIndex = -1;
555  tfScalar minVal = tfScalar(TF_LARGE_FLOAT);
556  if (m_floats[0] < minVal)
557  {
558  minIndex = 0;
559  minVal = m_floats[0];
560  }
561  if (m_floats[1] < minVal)
562  {
563  minIndex = 1;
564  minVal = m_floats[1];
565  }
566  if (m_floats[2] < minVal)
567  {
568  minIndex = 2;
569  minVal =m_floats[2];
570  }
571  if (m_floats[3] < minVal)
572  {
573  minIndex = 3;
574  minVal = m_floats[3];
575  }
576 
577  return minIndex;
578 
579  }
580 
581 
583  {
584  return absolute4().maxAxis4();
585  }
586 
587 
588 
589 
597 /* void getValue(tfScalar *m) const
598  {
599  m[0] = m_floats[0];
600  m[1] = m_floats[1];
601  m[2] =m_floats[2];
602  }
603 */
610  TFSIMD_FORCE_INLINE void setValue(const tfScalar& x, const tfScalar& y, const tfScalar& z,const tfScalar& w)
611  {
612  m_floats[0]=x;
613  m_floats[1]=y;
614  m_floats[2]=z;
615  m_floats[3]=w;
616  }
617 
618 
619 };
620 
621 
623 TFSIMD_FORCE_INLINE void tfSwapScalarEndian(const tfScalar& sourceVal, tfScalar& destVal)
624 {
625  unsigned char* dest = (unsigned char*) &destVal;
626  const unsigned char* src = (const unsigned char*) &sourceVal;
627  dest[0] = src[7];
628  dest[1] = src[6];
629  dest[2] = src[5];
630  dest[3] = src[4];
631  dest[4] = src[3];
632  dest[5] = src[2];
633  dest[6] = src[1];
634  dest[7] = src[0];
635 }
637 TFSIMD_FORCE_INLINE void tfSwapVector3Endian(const Vector3& sourceVec, Vector3& destVec)
638 {
639  for (int i=0;i<4;i++)
640  {
641  tfSwapScalarEndian(sourceVec[i],destVec[i]);
642  }
643 
644 }
645 
648 {
649 
650  Vector3 swappedVec;
651  for (int i=0;i<4;i++)
652  {
653  tfSwapScalarEndian(vector[i],swappedVec[i]);
654  }
655  vector = swappedVec;
656 }
657 
659 {
660  if (tfFabs(n.z()) > TFSIMDSQRT12) {
661  // choose p in y-z plane
662  tfScalar a = n[1]*n[1] + n[2]*n[2];
663  tfScalar k = tfRecipSqrt (a);
664  p.setValue(0,-n[2]*k,n[1]*k);
665  // set q = n x p
666  q.setValue(a*k,-n[0]*p[2],n[0]*p[1]);
667  }
668  else {
669  // choose p in x-y plane
670  tfScalar a = n.x()*n.x() + n.y()*n.y();
671  tfScalar k = tfRecipSqrt (a);
672  p.setValue(-n.y()*k,n.x()*k,0);
673  // set q = n x p
674  q.setValue(-n.z()*p.y(),n.z()*p.x(),a*k);
675  }
676 }
677 
678 
680 {
681  float m_floats[4];
682 };
683 
685 {
686  double m_floats[4];
687 
688 };
689 
690 TFSIMD_FORCE_INLINE void Vector3::serializeFloat(struct Vector3FloatData& dataOut) const
691 {
693  for (int i=0;i<4;i++)
694  dataOut.m_floats[i] = float(m_floats[i]);
695 }
696 
697 TFSIMD_FORCE_INLINE void Vector3::deSerializeFloat(const struct Vector3FloatData& dataIn)
698 {
699  for (int i=0;i<4;i++)
700  m_floats[i] = tfScalar(dataIn.m_floats[i]);
701 }
702 
703 
704 TFSIMD_FORCE_INLINE void Vector3::serializeDouble(struct Vector3DoubleData& dataOut) const
705 {
707  for (int i=0;i<4;i++)
708  dataOut.m_floats[i] = double(m_floats[i]);
709 }
710 
711 TFSIMD_FORCE_INLINE void Vector3::deSerializeDouble(const struct Vector3DoubleData& dataIn)
712 {
713  for (int i=0;i<4;i++)
714  m_floats[i] = tfScalar(dataIn.m_floats[i]);
715 }
716 
717 
718 TFSIMD_FORCE_INLINE void Vector3::serialize(struct Vector3Data& dataOut) const
719 {
721  for (int i=0;i<4;i++)
722  dataOut.m_floats[i] = m_floats[i];
723 }
724 
725 TFSIMD_FORCE_INLINE void Vector3::deSerialize(const struct Vector3Data& dataIn)
726 {
727  for (int i=0;i<4;i++)
728  m_floats[i] = dataIn.m_floats[i];
729 }
730 
731 }
732 
733 #endif //TFSIMD__VECTOR3_H
TFSIMD_FORCE_INLINE Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)
Definition: Matrix3x3.h:604
TFSIMD_FORCE_INLINE Quaternion operator-(const Quaternion &q)
Return the negative of a quaternion.
Definition: Quaternion.h:356
#define TF_LARGE_FLOAT
Definition: Scalar.h:162
double tfScalar
The tfScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition: Scalar.h:160
TFSIMD_FORCE_INLINE bool operator==(const Matrix3x3 &m1, const Matrix3x3 &m2)
Equality operator between two matrices It will test all elements are equal.
Definition: Matrix3x3.h:642
TFSIMD_FORCE_INLINE Vector3 operator/(const Vector3 &v, const tfScalar &s)
Return the vector inversely scaled by s.
Definition: Vector3.h:395
TFSIMD_FORCE_INLINE tfScalar tfDistance2(const Vector3 &v1, const Vector3 &v2)
Return the distance squared between two vectors.
Definition: Vector3.h:418
XmlRpcServer s
#define TFSIMD_EPSILON
Definition: Scalar.h:204
double m_floats[4]
Definition: Vector3.h:686
TFSIMD_FORCE_INLINE tfScalar tfTriple(const Vector3 &v1, const Vector3 &v2, const Vector3 &v3)
Definition: Vector3.h:446
Definition: exceptions.h:38
TFSIMD_FORCE_INLINE tfScalar tfDistance(const Vector3 &v1, const Vector3 &v2)
Return the distance between two vectors.
Definition: Vector3.h:426
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
Return the half angle between two quaternions.
Definition: Quaternion.h:407
tfScalar getW() const
Definition: Vector3.h:516
TFSIMD_FORCE_INLINE int maxAxis4() const
Definition: Vector3.h:519
TFSIMD_FORCE_INLINE void tfPlaneSpace1(const Vector3 &n, Vector3 &p, Vector3 &q)
Definition: Vector3.h:658
TFSIMD_FORCE_INLINE tfScalar tfCos(tfScalar x)
Definition: Scalar.h:181
TFSIMD_FORCE_INLINE tfScalar tfAcos(tfScalar x)
Definition: Scalar.h:184
void serialize(Stream &stream, const T &t)
TFSIMD_FORCE_INLINE tfVector4()
Definition: Vector3.h:495
TFSIMD_FORCE_INLINE void tfSwapScalarEndian(const tfScalar &sourceVal, tfScalar &destVal)
tfSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization ...
Definition: Vector3.h:623
TFSIMD_FORCE_INLINE tfScalar tfDot(const Vector3 &v1, const Vector3 &v2)
Return the dot product between two vectors.
Definition: Vector3.h:410
TFSIMD_FORCE_INLINE void tfSetMin(T &a, const T &b)
Definition: MinMax.h:34
TFSIMD_FORCE_INLINE int minAxis4() const
Definition: Vector3.h:552
TFSIMD_FORCE_INLINE void setValue(const tfScalar &x, const tfScalar &y, const tfScalar &z, const tfScalar &w)
Set x,y,z and zero w.
Definition: Vector3.h:610
TFSIMD_FORCE_INLINE Vector3 lerp(const Vector3 &v1, const Vector3 &v2, const tfScalar &t)
Return the linear interpolation between two vectors.
Definition: Vector3.h:456
#define tfRecipSqrt(x)
Definition: Scalar.h:201
TFSIMD_FORCE_INLINE Vector3 tfCross(const Vector3 &v1, const Vector3 &v2)
Return the cross product of two vectors.
Definition: Vector3.h:440
#define TFSIMD_FORCE_INLINE
Definition: Scalar.h:130
TFSIMD_FORCE_INLINE tfVector4 absolute4() const
Definition: Vector3.h:505
TFSIMD_FORCE_INLINE void tfSwapVector3Endian(const Vector3 &sourceVec, Vector3 &destVec)
tfSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization ...
Definition: Vector3.h:637
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
Calculate the dot product between two quaternions.
Definition: Quaternion.h:392
TFSIMD_FORCE_INLINE tfScalar tfAngle(const Vector3 &v1, const Vector3 &v2)
Return the angle between two vectors.
Definition: Vector3.h:433
TFSIMD_FORCE_INLINE tfScalar tfSqrt(tfScalar x)
Definition: Scalar.h:179
#define Vector3Data
Definition: Vector3.h:26
#define TFSIMDSQRT12
Definition: Scalar.h:199
TFSIMD_FORCE_INLINE tfVector4(const tfScalar &x, const tfScalar &y, const tfScalar &z, const tfScalar &w)
Definition: Vector3.h:498
TFSIMD_FORCE_INLINE Vector3 operator+(const Vector3 &v1, const Vector3 &v2)
Return the sum of two vectors (Point symantics)
Definition: Vector3.h:354
Vector3 can be used to represent 3D points and vectors. It has an un-used w component to suit 16-byte...
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
Return the length of a quaternion.
Definition: Quaternion.h:400
TFSIMD_FORCE_INLINE tfScalar tfSin(tfScalar x)
Definition: Scalar.h:182
TFSIMD_FORCE_INLINE void tfUnSwapVector3Endian(Vector3 &vector)
tfUnSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization ...
Definition: Vector3.h:647
TFSIMD_FORCE_INLINE int closestAxis4() const
Definition: Vector3.h:582
TFSIMD_FORCE_INLINE tfScalar tfFabs(tfScalar x)
Definition: Scalar.h:180
ATTRIBUTE_ALIGNED16(class) QuadWord
The QuadWord class is base class for Vector3 and Quaternion. Some issues under PS3 Linux with IBM 2...
Definition: QuadWord.h:34
TFSIMD_FORCE_INLINE void tfSetMax(T &a, const T &b)
Definition: MinMax.h:43
#define tfFullAssert(x)
Definition: Scalar.h:149
float m_floats[4]
Definition: Vector3.h:681


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Feb 28 2022 22:26:19