tf2  master
tf2 maintains the relationship between coordinate frames in a tree structure buffered in time, and lets the user transform points, vectors, etc between any two coordinate frames at any desired point in time.
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 TF2_VECTOR3_H
18 #define TF2_VECTOR3_H
19 
20 
21 #include "Scalar.h"
22 #include "MinMax.h"
23 #include "tf2/visibility_control.h"
24 
25 namespace tf2
26 {
27 
28 #define Vector3Data Vector3DoubleData
29 #define Vector3DataName "Vector3DoubleData"
30 
31 
32 
33 
38 ATTRIBUTE_ALIGNED16(class) Vector3
39 {
40 public:
41 
42 #if defined (__SPU__) && defined (__CELLOS_LV2__)
43  tf2Scalar m_floats[4];
44 public:
45  TF2SIMD_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 TF2_USE_SSE // _WIN32
52  union {
53  __m128 mVec128;
54  tf2Scalar m_floats[4];
55  };
56  TF2SIMD_FORCE_INLINE __m128 get128() const
57  {
58  return mVec128;
59  }
60  TF2SIMD_FORCE_INLINE void set128(__m128 v128)
61  {
62  mVec128 = v128;
63  }
64 #else
65  tf2Scalar m_floats[4];
66 #endif
67 #endif //__CELLOS_LV2__ __SPU__
68 
69  public:
70 
72  TF2SIMD_FORCE_INLINE Vector3() {}
73 
74 
75 
81  TF2SIMD_FORCE_INLINE Vector3(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z)
82  {
83  m_floats[0] = x;
84  m_floats[1] = y;
85  m_floats[2] = z;
86  m_floats[3] = tf2Scalar(0.);
87  }
88 
91  TF2SIMD_FORCE_INLINE Vector3& operator+=(const Vector3& v)
92  {
93 
94  m_floats[0] += v.m_floats[0]; m_floats[1] += v.m_floats[1];m_floats[2] += v.m_floats[2];
95  return *this;
96  }
97 
98 
101  TF2SIMD_FORCE_INLINE Vector3& operator-=(const Vector3& v)
102  {
103  m_floats[0] -= v.m_floats[0]; m_floats[1] -= v.m_floats[1];m_floats[2] -= v.m_floats[2];
104  return *this;
105  }
108  TF2SIMD_FORCE_INLINE Vector3& operator*=(const tf2Scalar& s)
109  {
110  m_floats[0] *= s; m_floats[1] *= s;m_floats[2] *= s;
111  return *this;
112  }
113 
116  TF2SIMD_FORCE_INLINE Vector3& operator/=(const tf2Scalar& s)
117  {
118  tf2FullAssert(s != tf2Scalar(0.0));
119  return *this *= tf2Scalar(1.0) / s;
120  }
121 
124  TF2SIMD_FORCE_INLINE tf2Scalar dot(const Vector3& v) const
125  {
126  return m_floats[0] * v.m_floats[0] + m_floats[1] * v.m_floats[1] +m_floats[2] * v.m_floats[2];
127  }
128 
130  TF2SIMD_FORCE_INLINE tf2Scalar length2() const
131  {
132  return dot(*this);
133  }
134 
137  {
138  return tf2Sqrt(length2());
139  }
140 
143  TF2SIMD_FORCE_INLINE tf2Scalar distance2(const Vector3& v) const;
144 
147  TF2SIMD_FORCE_INLINE tf2Scalar distance(const Vector3& v) const;
148 
151  TF2SIMD_FORCE_INLINE Vector3& normalize()
152  {
153  return *this /= length();
154  }
155 
157  TF2SIMD_FORCE_INLINE Vector3 normalized() const;
158 
162  TF2SIMD_FORCE_INLINE Vector3 rotate( const Vector3& wAxis, const tf2Scalar angle ) const;
163 
166  TF2SIMD_FORCE_INLINE tf2Scalar angle(const Vector3& v) const
167  {
168  tf2Scalar s = tf2Sqrt(length2() * v.length2());
169  tf2FullAssert(s != tf2Scalar(0.0));
170  return tf2Acos(dot(v) / s);
171  }
173  TF2SIMD_FORCE_INLINE Vector3 absolute() const
174  {
175  return Vector3(
176  tf2Fabs(m_floats[0]),
177  tf2Fabs(m_floats[1]),
178  tf2Fabs(m_floats[2]));
179  }
182  TF2SIMD_FORCE_INLINE Vector3 cross(const Vector3& v) const
183  {
184  return Vector3(
185  m_floats[1] * v.m_floats[2] -m_floats[2] * v.m_floats[1],
186  m_floats[2] * v.m_floats[0] - m_floats[0] * v.m_floats[2],
187  m_floats[0] * v.m_floats[1] - m_floats[1] * v.m_floats[0]);
188  }
189 
190  TF2SIMD_FORCE_INLINE tf2Scalar triple(const Vector3& v1, const Vector3& v2) const
191  {
192  return m_floats[0] * (v1.m_floats[1] * v2.m_floats[2] - v1.m_floats[2] * v2.m_floats[1]) +
193  m_floats[1] * (v1.m_floats[2] * v2.m_floats[0] - v1.m_floats[0] * v2.m_floats[2]) +
194  m_floats[2] * (v1.m_floats[0] * v2.m_floats[1] - v1.m_floats[1] * v2.m_floats[0]);
195  }
196 
199  TF2SIMD_FORCE_INLINE int minAxis() const
200  {
201  return m_floats[0] < m_floats[1] ? (m_floats[0] <m_floats[2] ? 0 : 2) : (m_floats[1] <m_floats[2] ? 1 : 2);
202  }
203 
206  TF2SIMD_FORCE_INLINE int maxAxis() const
207  {
208  return m_floats[0] < m_floats[1] ? (m_floats[1] <m_floats[2] ? 2 : 1) : (m_floats[0] <m_floats[2] ? 2 : 0);
209  }
210 
211  TF2SIMD_FORCE_INLINE int furthestAxis() const
212  {
213  return absolute().minAxis();
214  }
215 
216  TF2SIMD_FORCE_INLINE int closestAxis() const
217  {
218  return absolute().maxAxis();
219  }
220 
221  TF2SIMD_FORCE_INLINE void setInterpolate3(const Vector3& v0, const Vector3& v1, tf2Scalar rt)
222  {
223  tf2Scalar s = tf2Scalar(1.0) - rt;
224  m_floats[0] = s * v0.m_floats[0] + rt * v1.m_floats[0];
225  m_floats[1] = s * v0.m_floats[1] + rt * v1.m_floats[1];
226  m_floats[2] = s * v0.m_floats[2] + rt * v1.m_floats[2];
227  //don't do the unused w component
228  // m_co[3] = s * v0[3] + rt * v1[3];
229  }
230 
234  TF2SIMD_FORCE_INLINE Vector3 lerp(const Vector3& v, const tf2Scalar& t) const
235  {
236  return Vector3(m_floats[0] + (v.m_floats[0] - m_floats[0]) * t,
237  m_floats[1] + (v.m_floats[1] - m_floats[1]) * t,
238  m_floats[2] + (v.m_floats[2] -m_floats[2]) * t);
239  }
240 
243  TF2SIMD_FORCE_INLINE Vector3& operator*=(const Vector3& v)
244  {
245  m_floats[0] *= v.m_floats[0]; m_floats[1] *= v.m_floats[1];m_floats[2] *= v.m_floats[2];
246  return *this;
247  }
248 
250  TF2SIMD_FORCE_INLINE const tf2Scalar& getX() const { return m_floats[0]; }
252  TF2SIMD_FORCE_INLINE const tf2Scalar& getY() const { return m_floats[1]; }
254  TF2SIMD_FORCE_INLINE const tf2Scalar& getZ() const { return m_floats[2]; }
256  TF2SIMD_FORCE_INLINE void setX(tf2Scalar x) { m_floats[0] = x;};
258  TF2SIMD_FORCE_INLINE void setY(tf2Scalar y) { m_floats[1] = y;};
260  TF2SIMD_FORCE_INLINE void setZ(tf2Scalar z) {m_floats[2] = z;};
262  TF2SIMD_FORCE_INLINE void setW(tf2Scalar w) { m_floats[3] = w;};
264  TF2SIMD_FORCE_INLINE const tf2Scalar& x() const { return m_floats[0]; }
266  TF2SIMD_FORCE_INLINE const tf2Scalar& y() const { return m_floats[1]; }
268  TF2SIMD_FORCE_INLINE const tf2Scalar& z() const { return m_floats[2]; }
270  TF2SIMD_FORCE_INLINE const tf2Scalar& w() const { return m_floats[3]; }
271 
272  //TF2SIMD_FORCE_INLINE tf2Scalar& operator[](int i) { return (&m_floats[0])[i]; }
273  //TF2SIMD_FORCE_INLINE const tf2Scalar& operator[](int i) const { return (&m_floats[0])[i]; }
275  TF2SIMD_FORCE_INLINE operator tf2Scalar *() { return &m_floats[0]; }
276  TF2SIMD_FORCE_INLINE operator const tf2Scalar *() const { return &m_floats[0]; }
277 
278  TF2SIMD_FORCE_INLINE bool operator==(const Vector3& other) const
279  {
280  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]));
281  }
282 
283  TF2SIMD_FORCE_INLINE bool operator!=(const Vector3& other) const
284  {
285  return !(*this == other);
286  }
287 
291  TF2SIMD_FORCE_INLINE void setMax(const Vector3& other)
292  {
293  tf2SetMax(m_floats[0], other.m_floats[0]);
294  tf2SetMax(m_floats[1], other.m_floats[1]);
295  tf2SetMax(m_floats[2], other.m_floats[2]);
296  tf2SetMax(m_floats[3], other.w());
297  }
301  TF2SIMD_FORCE_INLINE void setMin(const Vector3& other)
302  {
303  tf2SetMin(m_floats[0], other.m_floats[0]);
304  tf2SetMin(m_floats[1], other.m_floats[1]);
305  tf2SetMin(m_floats[2], other.m_floats[2]);
306  tf2SetMin(m_floats[3], other.w());
307  }
308 
309  TF2SIMD_FORCE_INLINE void setValue(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z)
310  {
311  m_floats[0]=x;
312  m_floats[1]=y;
313  m_floats[2]=z;
314  m_floats[3] = tf2Scalar(0.);
315  }
316 
317  TF2_PUBLIC
318  void getSkewSymmetricMatrix(Vector3* v0,Vector3* v1,Vector3* v2) const
319  {
320  v0->setValue(0. ,-z() ,y());
321  v1->setValue(z() ,0. ,-x());
322  v2->setValue(-y() ,x() ,0.);
323  }
324 
325  TF2_PUBLIC
326  void setZero()
327  {
328  setValue(tf2Scalar(0.),tf2Scalar(0.),tf2Scalar(0.));
329  }
330 
331  TF2SIMD_FORCE_INLINE bool isZero() const
332  {
333  return m_floats[0] == tf2Scalar(0) && m_floats[1] == tf2Scalar(0) && m_floats[2] == tf2Scalar(0);
334  }
335 
336  TF2SIMD_FORCE_INLINE bool fuzzyZero() const
337  {
338  return length2() < TF2SIMD_EPSILON;
339  }
340 
341  TF2SIMD_FORCE_INLINE void serialize(struct Vector3Data& dataOut) const;
342 
343  TF2SIMD_FORCE_INLINE void deSerialize(const struct Vector3Data& dataIn);
344 
345  TF2SIMD_FORCE_INLINE void serializeFloat(struct Vector3FloatData& dataOut) const;
346 
347  TF2SIMD_FORCE_INLINE void deSerializeFloat(const struct Vector3FloatData& dataIn);
348 
349  TF2SIMD_FORCE_INLINE void serializeDouble(struct Vector3DoubleData& dataOut) const;
350 
351  TF2SIMD_FORCE_INLINE void deSerializeDouble(const struct Vector3DoubleData& dataIn);
352 
353 };
354 
356 TF2SIMD_FORCE_INLINE Vector3
357 operator+(const Vector3& v1, const Vector3& v2)
358 {
359  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]);
360 }
361 
363 TF2SIMD_FORCE_INLINE Vector3
364 operator*(const Vector3& v1, const Vector3& v2)
365 {
366  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]);
367 }
368 
370 TF2SIMD_FORCE_INLINE Vector3
371 operator-(const Vector3& v1, const Vector3& v2)
372 {
373  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]);
374 }
376 TF2SIMD_FORCE_INLINE Vector3
377 operator-(const Vector3& v)
378 {
379  return Vector3(-v.m_floats[0], -v.m_floats[1], -v.m_floats[2]);
380 }
381 
383 TF2SIMD_FORCE_INLINE Vector3
384 operator*(const Vector3& v, const tf2Scalar& s)
385 {
386  return Vector3(v.m_floats[0] * s, v.m_floats[1] * s, v.m_floats[2] * s);
387 }
388 
390 TF2SIMD_FORCE_INLINE Vector3
391 operator*(const tf2Scalar& s, const Vector3& v)
392 {
393  return v * s;
394 }
395 
397 TF2SIMD_FORCE_INLINE Vector3
398 operator/(const Vector3& v, const tf2Scalar& s)
399 {
400  tf2FullAssert(s != tf2Scalar(0.0));
401  return v * (tf2Scalar(1.0) / s);
402 }
403 
405 TF2SIMD_FORCE_INLINE Vector3
406 operator/(const Vector3& v1, const Vector3& v2)
407 {
408  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]);
409 }
410 
413 tf2Dot(const Vector3& v1, const Vector3& v2)
414 {
415  return v1.dot(v2);
416 }
417 
418 
421 tf2Distance2(const Vector3& v1, const Vector3& v2)
422 {
423  return v1.distance2(v2);
424 }
425 
426 
429 tf2Distance(const Vector3& v1, const Vector3& v2)
430 {
431  return v1.distance(v2);
432 }
433 
436 tf2Angle(const Vector3& v1, const Vector3& v2)
437 {
438  return v1.angle(v2);
439 }
440 
442 TF2SIMD_FORCE_INLINE Vector3
443 tf2Cross(const Vector3& v1, const Vector3& v2)
444 {
445  return v1.cross(v2);
446 }
447 
449 tf2Triple(const Vector3& v1, const Vector3& v2, const Vector3& v3)
450 {
451  return v1.triple(v2, v3);
452 }
453 
458 TF2SIMD_FORCE_INLINE Vector3
459 lerp(const Vector3& v1, const Vector3& v2, const tf2Scalar& t)
460 {
461  return v1.lerp(v2, t);
462 }
463 
464 
465 
466 TF2SIMD_FORCE_INLINE tf2Scalar Vector3::distance2(const Vector3& v) const
467 {
468  return (v - *this).length2();
469 }
470 
471 TF2SIMD_FORCE_INLINE tf2Scalar Vector3::distance(const Vector3& v) const
472 {
473  return (v - *this).length();
474 }
475 
476 TF2SIMD_FORCE_INLINE Vector3 Vector3::normalized() const
477 {
478  return *this / length();
479 }
480 
481 TF2SIMD_FORCE_INLINE Vector3 Vector3::rotate( const Vector3& wAxis, const tf2Scalar angle ) const
482 {
483  // wAxis must be a unit lenght vector
484 
485  Vector3 o = wAxis * wAxis.dot( *this );
486  Vector3 x = *this - o;
487  Vector3 y;
488 
489  y = wAxis.cross( *this );
490 
491  return ( o + x * tf2Cos( angle ) + y * tf2Sin( angle ) );
492 }
493 
494 class tf2Vector4 : public Vector3
495 {
496 public:
497 
499 
500 
501  TF2SIMD_FORCE_INLINE tf2Vector4(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z,const tf2Scalar& w)
502  : Vector3(x,y,z)
503  {
504  m_floats[3] = w;
505  }
506 
507 
509  {
510  return tf2Vector4(
511  tf2Fabs(m_floats[0]),
512  tf2Fabs(m_floats[1]),
513  tf2Fabs(m_floats[2]),
514  tf2Fabs(m_floats[3]));
515  }
516 
517 
518 
519  TF2_PUBLIC
520  tf2Scalar getW() const { return m_floats[3];}
521 
522 
524  {
525  int maxIndex = -1;
527  if (m_floats[0] > maxVal)
528  {
529  maxIndex = 0;
530  maxVal = m_floats[0];
531  }
532  if (m_floats[1] > maxVal)
533  {
534  maxIndex = 1;
535  maxVal = m_floats[1];
536  }
537  if (m_floats[2] > maxVal)
538  {
539  maxIndex = 2;
540  maxVal =m_floats[2];
541  }
542  if (m_floats[3] > maxVal)
543  {
544  maxIndex = 3;
545  }
546 
547 
548 
549 
550  return maxIndex;
551 
552  }
553 
554 
556  {
557  int minIndex = -1;
559  if (m_floats[0] < minVal)
560  {
561  minIndex = 0;
562  minVal = m_floats[0];
563  }
564  if (m_floats[1] < minVal)
565  {
566  minIndex = 1;
567  minVal = m_floats[1];
568  }
569  if (m_floats[2] < minVal)
570  {
571  minIndex = 2;
572  minVal =m_floats[2];
573  }
574  if (m_floats[3] < minVal)
575  {
576  minIndex = 3;
577  }
578 
579  return minIndex;
580 
581  }
582 
583 
585  {
586  return absolute4().maxAxis4();
587  }
588 
589 
590 
591 
599 /* void getValue(tf2Scalar *m) const
600  {
601  m[0] = m_floats[0];
602  m[1] = m_floats[1];
603  m[2] =m_floats[2];
604  }
605 */
612  TF2SIMD_FORCE_INLINE void setValue(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z,const tf2Scalar& w)
613  {
614  m_floats[0]=x;
615  m_floats[1]=y;
616  m_floats[2]=z;
617  m_floats[3]=w;
618  }
619 
620 
621 };
622 
623 
626 {
627  unsigned char* dest = (unsigned char*) &destVal;
628  const unsigned char* src = reinterpret_cast<const unsigned char*>(&sourceVal);
629  dest[0] = src[7];
630  dest[1] = src[6];
631  dest[2] = src[5];
632  dest[3] = src[4];
633  dest[4] = src[3];
634  dest[5] = src[2];
635  dest[6] = src[1];
636  dest[7] = src[0];
637 }
639 TF2SIMD_FORCE_INLINE void tf2SwapVector3Endian(const Vector3& sourceVec, Vector3& destVec)
640 {
641  for (int i=0;i<4;i++)
642  {
643  tf2SwapScalarEndian(sourceVec[i],destVec[i]);
644  }
645 
646 }
647 
650 {
651 
652  Vector3 swappedVec;
653  for (int i=0;i<4;i++)
654  {
655  tf2SwapScalarEndian(vector[i],swappedVec[i]);
656  }
657  vector = swappedVec;
658 }
659 
660 TF2SIMD_FORCE_INLINE void tf2PlaneSpace1 (const Vector3& n, Vector3& p, Vector3& q)
661 {
662  if (tf2Fabs(n.z()) > TF2SIMDSQRT12) {
663  // choose p in y-z plane
664  tf2Scalar a = n[1]*n[1] + n[2]*n[2];
665  tf2Scalar k = tf2RecipSqrt (a);
666  p.setValue(0,-n[2]*k,n[1]*k);
667  // set q = n x p
668  q.setValue(a*k,-n[0]*p[2],n[0]*p[1]);
669  }
670  else {
671  // choose p in x-y plane
672  tf2Scalar a = n.x()*n.x() + n.y()*n.y();
673  tf2Scalar k = tf2RecipSqrt (a);
674  p.setValue(-n.y()*k,n.x()*k,0);
675  // set q = n x p
676  q.setValue(-n.z()*p.y(),n.z()*p.x(),a*k);
677  }
678 }
679 
680 
682 {
683  float m_floats[4];
684 };
685 
687 {
688  double m_floats[4];
689 
690 };
691 
692 TF2SIMD_FORCE_INLINE void Vector3::serializeFloat(struct Vector3FloatData& dataOut) const
693 {
695  for (int i=0;i<4;i++)
696  dataOut.m_floats[i] = float(m_floats[i]);
697 }
698 
699 TF2SIMD_FORCE_INLINE void Vector3::deSerializeFloat(const struct Vector3FloatData& dataIn)
700 {
701  for (int i=0;i<4;i++)
702  m_floats[i] = tf2Scalar(dataIn.m_floats[i]);
703 }
704 
705 
706 TF2SIMD_FORCE_INLINE void Vector3::serializeDouble(struct Vector3DoubleData& dataOut) const
707 {
709  for (int i=0;i<4;i++)
710  dataOut.m_floats[i] = double(m_floats[i]);
711 }
712 
713 TF2SIMD_FORCE_INLINE void Vector3::deSerializeDouble(const struct Vector3DoubleData& dataIn)
714 {
715  for (int i=0;i<4;i++)
716  m_floats[i] = tf2Scalar(dataIn.m_floats[i]);
717 }
718 
719 
720 TF2SIMD_FORCE_INLINE void Vector3::serialize(struct Vector3Data& dataOut) const
721 {
723  for (int i=0;i<4;i++)
724  dataOut.m_floats[i] = m_floats[i];
725 }
726 
727 TF2SIMD_FORCE_INLINE void Vector3::deSerialize(const struct Vector3Data& dataIn)
728 {
729  for (int i=0;i<4;i++)
730  m_floats[i] = dataIn.m_floats[i];
731 }
732 
733 }
734 
735 #endif //TF2_VECTOR3_H
tf2::tf2SwapScalarEndian
TF2SIMD_FORCE_INLINE void tf2SwapScalarEndian(const tf2Scalar &sourceVal, tf2Scalar &destVal)
tf2SwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization
Definition: Vector3.h:625
tf2::tf2Vector4::tf2Vector4
TF2SIMD_FORCE_INLINE tf2Vector4(const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z, const tf2Scalar &w)
Definition: Vector3.h:501
tf2::dot
TF2SIMD_FORCE_INLINE tf2Scalar dot(const Quaternion &q1, const Quaternion &q2)
Calculate the dot product between two quaternions.
Definition: Quaternion.h:395
Scalar.h
tf2::Vector3FloatData::m_floats
float m_floats[4]
Definition: Vector3.h:683
tf2::tf2Vector4::closestAxis4
TF2SIMD_FORCE_INLINE int closestAxis4() const
Definition: Vector3.h:584
tf2::operator/
TF2SIMD_FORCE_INLINE Vector3 operator/(const Vector3 &v, const tf2Scalar &s)
Return the vector inversely scaled by s.
Definition: Vector3.h:398
tf2::tf2UnSwapVector3Endian
TF2SIMD_FORCE_INLINE void tf2UnSwapVector3Endian(Vector3 &vector)
tf2UnSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization
Definition: Vector3.h:649
TF2SIMD_EPSILON
#define TF2SIMD_EPSILON
Definition: Scalar.h:202
tf2::tf2Vector4::maxAxis4
TF2SIMD_FORCE_INLINE int maxAxis4() const
Definition: Vector3.h:523
tf2Sin
TF2SIMD_FORCE_INLINE tf2Scalar tf2Sin(tf2Scalar x)
Definition: Scalar.h:180
tf2::tf2Dot
TF2SIMD_FORCE_INLINE tf2Scalar tf2Dot(const Vector3 &v1, const Vector3 &v2)
Return the dot product between two vectors.
Definition: Vector3.h:413
tf2::tf2Vector4::minAxis4
TF2SIMD_FORCE_INLINE int minAxis4() const
Definition: Vector3.h:555
tf2::lerp
TF2SIMD_FORCE_INLINE Vector3 lerp(const Vector3 &v1, const Vector3 &v2, const tf2Scalar &t)
Return the linear interpolation between two vectors.
Definition: Vector3.h:459
tf2::Vector3DoubleData
Definition: Vector3.h:686
tf2::tf2Vector4::setValue
TF2SIMD_FORCE_INLINE void setValue(const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z, const tf2Scalar &w)
Set x,y,z and zero w.
Definition: Vector3.h:612
tf2::tf2Vector4::tf2Vector4
TF2SIMD_FORCE_INLINE tf2Vector4()
Definition: Vector3.h:498
tf2Sqrt
TF2SIMD_FORCE_INLINE tf2Scalar tf2Sqrt(tf2Scalar x)
Definition: Scalar.h:177
MinMax.h
tf2::Vector3FloatData
Definition: Vector3.h:681
tf2::ATTRIBUTE_ALIGNED16
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
tf2FullAssert
#define tf2FullAssert(x)
Definition: Scalar.h:148
tf2::tf2Distance2
TF2SIMD_FORCE_INLINE tf2Scalar tf2Distance2(const Vector3 &v1, const Vector3 &v2)
Return the distance squared between two vectors.
Definition: Vector3.h:421
TF2_LARGE_FLOAT
#define TF2_LARGE_FLOAT
Definition: Scalar.h:161
tf2::tf2Angle
TF2SIMD_FORCE_INLINE tf2Scalar tf2Angle(const Vector3 &v1, const Vector3 &v2)
Return the angle between two vectors.
Definition: Vector3.h:436
tf2::tf2Vector4::getW
tf2Scalar getW() const
Definition: Vector3.h:520
tf2Acos
TF2SIMD_FORCE_INLINE tf2Scalar tf2Acos(tf2Scalar x)
Definition: Scalar.h:182
tf2::tf2Cross
TF2SIMD_FORCE_INLINE Vector3 tf2Cross(const Vector3 &v1, const Vector3 &v2)
Return the cross product of two vectors.
Definition: Vector3.h:443
tf2::operator==
TF2SIMD_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:649
tf2::operator*
TF2SIMD_FORCE_INLINE Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)
Definition: Matrix3x3.h:611
tf2::tf2SwapVector3Endian
TF2SIMD_FORCE_INLINE void tf2SwapVector3Endian(const Vector3 &sourceVec, Vector3 &destVec)
tf2SwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization
Definition: Vector3.h:639
tf2RecipSqrt
#define tf2RecipSqrt(x)
Definition: Scalar.h:199
TF2SIMD_FORCE_INLINE
#define TF2SIMD_FORCE_INLINE
Definition: Scalar.h:129
tf2::tf2PlaneSpace1
TF2SIMD_FORCE_INLINE void tf2PlaneSpace1(const Vector3 &n, Vector3 &p, Vector3 &q)
Definition: Vector3.h:660
tf2SetMin
TF2SIMD_FORCE_INLINE void tf2SetMin(T &a, const T &b)
Definition: MinMax.h:39
visibility_control.h
Vector3Data
#define Vector3Data
Definition: Vector3.h:28
tf2Cos
TF2SIMD_FORCE_INLINE tf2Scalar tf2Cos(tf2Scalar x)
Definition: Scalar.h:179
tf2::tf2Triple
TF2SIMD_FORCE_INLINE tf2Scalar tf2Triple(const Vector3 &v1, const Vector3 &v2, const Vector3 &v3)
Definition: Vector3.h:449
tf2
Definition: buffer_core.h:55
tf2Fabs
TF2SIMD_FORCE_INLINE tf2Scalar tf2Fabs(tf2Scalar x)
Definition: Scalar.h:178
TF2_PUBLIC
#define TF2_PUBLIC
Definition: visibility_control.h:58
tf2::angle
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
Return the half angle between two quaternions.
Definition: Quaternion.h:410
tf2::operator+
TF2SIMD_FORCE_INLINE Vector3 operator+(const Vector3 &v1, const Vector3 &v2)
Return the sum of two vectors (Point symantics)
Definition: Vector3.h:357
tf2::tf2Vector4
Definition: Vector3.h:494
tf2::length
TF2SIMD_FORCE_INLINE tf2Scalar length(const Quaternion &q)
Return the length of a quaternion.
Definition: Quaternion.h:403
tf2Scalar
double tf2Scalar
The tf2Scalar type abstracts floating point numbers, to easily switch between double and single float...
Definition: Scalar.h:159
tf2::tf2Distance
TF2SIMD_FORCE_INLINE tf2Scalar tf2Distance(const Vector3 &v1, const Vector3 &v2)
Return the distance between two vectors.
Definition: Vector3.h:429
tf2::operator-
TF2SIMD_FORCE_INLINE Quaternion operator-(const Quaternion &q)
Return the negative of a quaternion.
Definition: Quaternion.h:359
TF2SIMDSQRT12
#define TF2SIMDSQRT12
Definition: Scalar.h:197
tf2SetMax
TF2SIMD_FORCE_INLINE void tf2SetMax(T &a, const T &b)
Definition: MinMax.h:48
tf2::tf2Vector4::absolute4
TF2SIMD_FORCE_INLINE tf2Vector4 absolute4() const
Definition: Vector3.h:508
tf2::Vector3DoubleData::m_floats
double m_floats[4]
Definition: Vector3.h:688