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 
24 namespace tf2
25 {
26 
27 #define Vector3Data Vector3DoubleData
28 #define Vector3DataName "Vector3DoubleData"
29 
30 
31 
32 
37 ATTRIBUTE_ALIGNED16(class) Vector3
38 {
39 public:
40 
41 #if defined (__SPU__) && defined (__CELLOS_LV2__)
42  tf2Scalar m_floats[4];
43 public:
44  TF2SIMD_FORCE_INLINE const vec_float4& get128() const
45  {
46  return *((const vec_float4*)&m_floats[0]);
47  }
48 public:
49 #else //__CELLOS_LV2__ __SPU__
50 #ifdef TF2_USE_SSE // _WIN32
51  union {
52  __m128 mVec128;
53  tf2Scalar m_floats[4];
54  };
55  TF2SIMD_FORCE_INLINE __m128 get128() const
56  {
57  return mVec128;
58  }
59  TF2SIMD_FORCE_INLINE void set128(__m128 v128)
60  {
61  mVec128 = v128;
62  }
63 #else
64  tf2Scalar m_floats[4];
65 #endif
66 #endif //__CELLOS_LV2__ __SPU__
67 
68  public:
69 
71  TF2SIMD_FORCE_INLINE Vector3() {}
72 
73 
74 
80  TF2SIMD_FORCE_INLINE Vector3(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z)
81  {
82  m_floats[0] = x;
83  m_floats[1] = y;
84  m_floats[2] = z;
85  m_floats[3] = tf2Scalar(0.);
86  }
87 
90  TF2SIMD_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  TF2SIMD_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  TF2SIMD_FORCE_INLINE Vector3& operator*=(const tf2Scalar& s)
108  {
109  m_floats[0] *= s; m_floats[1] *= s;m_floats[2] *= s;
110  return *this;
111  }
112 
115  TF2SIMD_FORCE_INLINE Vector3& operator/=(const tf2Scalar& s)
116  {
117  tf2FullAssert(s != tf2Scalar(0.0));
118  return *this *= tf2Scalar(1.0) / s;
119  }
120 
123  TF2SIMD_FORCE_INLINE tf2Scalar 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  TF2SIMD_FORCE_INLINE tf2Scalar length2() const
130  {
131  return dot(*this);
132  }
133 
136  {
137  return tf2Sqrt(length2());
138  }
139 
142  TF2SIMD_FORCE_INLINE tf2Scalar distance2(const Vector3& v) const;
143 
146  TF2SIMD_FORCE_INLINE tf2Scalar distance(const Vector3& v) const;
147 
150  TF2SIMD_FORCE_INLINE Vector3& normalize()
151  {
152  return *this /= length();
153  }
154 
156  TF2SIMD_FORCE_INLINE Vector3 normalized() const;
157 
161  TF2SIMD_FORCE_INLINE Vector3 rotate( const Vector3& wAxis, const tf2Scalar angle ) const;
162 
165  TF2SIMD_FORCE_INLINE tf2Scalar angle(const Vector3& v) const
166  {
167  tf2Scalar s = tf2Sqrt(length2() * v.length2());
168  tf2FullAssert(s != tf2Scalar(0.0));
169  return tf2Acos(dot(v) / s);
170  }
172  TF2SIMD_FORCE_INLINE Vector3 absolute() const
173  {
174  return Vector3(
175  tf2Fabs(m_floats[0]),
176  tf2Fabs(m_floats[1]),
177  tf2Fabs(m_floats[2]));
178  }
181  TF2SIMD_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  TF2SIMD_FORCE_INLINE tf2Scalar 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  TF2SIMD_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  TF2SIMD_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  TF2SIMD_FORCE_INLINE int furthestAxis() const
211  {
212  return absolute().minAxis();
213  }
214 
215  TF2SIMD_FORCE_INLINE int closestAxis() const
216  {
217  return absolute().maxAxis();
218  }
219 
220  TF2SIMD_FORCE_INLINE void setInterpolate3(const Vector3& v0, const Vector3& v1, tf2Scalar rt)
221  {
222  tf2Scalar s = tf2Scalar(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  TF2SIMD_FORCE_INLINE Vector3 lerp(const Vector3& v, const tf2Scalar& 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  TF2SIMD_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  TF2SIMD_FORCE_INLINE const tf2Scalar& getX() const { return m_floats[0]; }
251  TF2SIMD_FORCE_INLINE const tf2Scalar& getY() const { return m_floats[1]; }
253  TF2SIMD_FORCE_INLINE const tf2Scalar& getZ() const { return m_floats[2]; }
255  TF2SIMD_FORCE_INLINE void setX(tf2Scalar x) { m_floats[0] = x;};
257  TF2SIMD_FORCE_INLINE void setY(tf2Scalar y) { m_floats[1] = y;};
259  TF2SIMD_FORCE_INLINE void setZ(tf2Scalar z) {m_floats[2] = z;};
261  TF2SIMD_FORCE_INLINE void setW(tf2Scalar w) { m_floats[3] = w;};
263  TF2SIMD_FORCE_INLINE const tf2Scalar& x() const { return m_floats[0]; }
265  TF2SIMD_FORCE_INLINE const tf2Scalar& y() const { return m_floats[1]; }
267  TF2SIMD_FORCE_INLINE const tf2Scalar& z() const { return m_floats[2]; }
269  TF2SIMD_FORCE_INLINE const tf2Scalar& w() const { return m_floats[3]; }
270 
271  //TF2SIMD_FORCE_INLINE tf2Scalar& operator[](int i) { return (&m_floats[0])[i]; }
272  //TF2SIMD_FORCE_INLINE const tf2Scalar& operator[](int i) const { return (&m_floats[0])[i]; }
274  TF2SIMD_FORCE_INLINE operator tf2Scalar *() { return &m_floats[0]; }
275  TF2SIMD_FORCE_INLINE operator const tf2Scalar *() const { return &m_floats[0]; }
276 
277  TF2SIMD_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  TF2SIMD_FORCE_INLINE bool operator!=(const Vector3& other) const
283  {
284  return !(*this == other);
285  }
286 
290  TF2SIMD_FORCE_INLINE void setMax(const Vector3& other)
291  {
292  tf2SetMax(m_floats[0], other.m_floats[0]);
293  tf2SetMax(m_floats[1], other.m_floats[1]);
294  tf2SetMax(m_floats[2], other.m_floats[2]);
295  tf2SetMax(m_floats[3], other.w());
296  }
300  TF2SIMD_FORCE_INLINE void setMin(const Vector3& other)
301  {
302  tf2SetMin(m_floats[0], other.m_floats[0]);
303  tf2SetMin(m_floats[1], other.m_floats[1]);
304  tf2SetMin(m_floats[2], other.m_floats[2]);
305  tf2SetMin(m_floats[3], other.w());
306  }
307 
308  TF2SIMD_FORCE_INLINE void setValue(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z)
309  {
310  m_floats[0]=x;
311  m_floats[1]=y;
312  m_floats[2]=z;
313  m_floats[3] = tf2Scalar(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(tf2Scalar(0.),tf2Scalar(0.),tf2Scalar(0.));
326  }
327 
328  TF2SIMD_FORCE_INLINE bool isZero() const
329  {
330  return m_floats[0] == tf2Scalar(0) && m_floats[1] == tf2Scalar(0) && m_floats[2] == tf2Scalar(0);
331  }
332 
333  TF2SIMD_FORCE_INLINE bool fuzzyZero() const
334  {
335  return length2() < TF2SIMD_EPSILON;
336  }
337 
338  TF2SIMD_FORCE_INLINE void serialize(struct Vector3Data& dataOut) const;
339 
340  TF2SIMD_FORCE_INLINE void deSerialize(const struct Vector3Data& dataIn);
341 
342  TF2SIMD_FORCE_INLINE void serializeFloat(struct Vector3FloatData& dataOut) const;
343 
344  TF2SIMD_FORCE_INLINE void deSerializeFloat(const struct Vector3FloatData& dataIn);
345 
346  TF2SIMD_FORCE_INLINE void serializeDouble(struct Vector3DoubleData& dataOut) const;
347 
348  TF2SIMD_FORCE_INLINE void deSerializeDouble(const struct Vector3DoubleData& dataIn);
349 
350 };
351 
353 TF2SIMD_FORCE_INLINE Vector3
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 
360 TF2SIMD_FORCE_INLINE Vector3
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 
367 TF2SIMD_FORCE_INLINE Vector3
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 }
373 TF2SIMD_FORCE_INLINE Vector3
374 operator-(const Vector3& v)
375 {
376  return Vector3(-v.m_floats[0], -v.m_floats[1], -v.m_floats[2]);
377 }
378 
380 TF2SIMD_FORCE_INLINE Vector3
381 operator*(const Vector3& v, const tf2Scalar& s)
382 {
383  return Vector3(v.m_floats[0] * s, v.m_floats[1] * s, v.m_floats[2] * s);
384 }
385 
387 TF2SIMD_FORCE_INLINE Vector3
388 operator*(const tf2Scalar& s, const Vector3& v)
389 {
390  return v * s;
391 }
392 
394 TF2SIMD_FORCE_INLINE Vector3
395 operator/(const Vector3& v, const tf2Scalar& s)
396 {
397  tf2FullAssert(s != tf2Scalar(0.0));
398  return v * (tf2Scalar(1.0) / s);
399 }
400 
402 TF2SIMD_FORCE_INLINE Vector3
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 tf2Dot(const Vector3& v1, const Vector3& v2)
411 {
412  return v1.dot(v2);
413 }
414 
415 
418 tf2Distance2(const Vector3& v1, const Vector3& v2)
419 {
420  return v1.distance2(v2);
421 }
422 
423 
426 tf2Distance(const Vector3& v1, const Vector3& v2)
427 {
428  return v1.distance(v2);
429 }
430 
433 tf2Angle(const Vector3& v1, const Vector3& v2)
434 {
435  return v1.angle(v2);
436 }
437 
439 TF2SIMD_FORCE_INLINE Vector3
440 tf2Cross(const Vector3& v1, const Vector3& v2)
441 {
442  return v1.cross(v2);
443 }
444 
446 tf2Triple(const Vector3& v1, const Vector3& v2, const Vector3& v3)
447 {
448  return v1.triple(v2, v3);
449 }
450 
455 TF2SIMD_FORCE_INLINE Vector3
456 lerp(const Vector3& v1, const Vector3& v2, const tf2Scalar& t)
457 {
458  return v1.lerp(v2, t);
459 }
460 
461 
462 
463 TF2SIMD_FORCE_INLINE tf2Scalar Vector3::distance2(const Vector3& v) const
464 {
465  return (v - *this).length2();
466 }
467 
468 TF2SIMD_FORCE_INLINE tf2Scalar Vector3::distance(const Vector3& v) const
469 {
470  return (v - *this).length();
471 }
472 
473 TF2SIMD_FORCE_INLINE Vector3 Vector3::normalized() const
474 {
475  return *this / length();
476 }
477 
478 TF2SIMD_FORCE_INLINE Vector3 Vector3::rotate( const Vector3& wAxis, const tf2Scalar 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 * tf2Cos( angle ) + y * tf2Sin( angle ) );
489 }
490 
491 class tf2Vector4 : public Vector3
492 {
493 public:
494 
496 
497 
498  TF2SIMD_FORCE_INLINE tf2Vector4(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z,const tf2Scalar& w)
499  : Vector3(x,y,z)
500  {
501  m_floats[3] = w;
502  }
503 
504 
506  {
507  return tf2Vector4(
508  tf2Fabs(m_floats[0]),
509  tf2Fabs(m_floats[1]),
510  tf2Fabs(m_floats[2]),
511  tf2Fabs(m_floats[3]));
512  }
513 
514 
515 
516  tf2Scalar getW() const { return m_floats[3];}
517 
518 
520  {
521  int maxIndex = -1;
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  }
542 
543 
544 
545 
546  return maxIndex;
547 
548  }
549 
550 
552  {
553  int minIndex = -1;
555  if (m_floats[0] < minVal)
556  {
557  minIndex = 0;
558  minVal = m_floats[0];
559  }
560  if (m_floats[1] < minVal)
561  {
562  minIndex = 1;
563  minVal = m_floats[1];
564  }
565  if (m_floats[2] < minVal)
566  {
567  minIndex = 2;
568  minVal =m_floats[2];
569  }
570  if (m_floats[3] < minVal)
571  {
572  minIndex = 3;
573  }
574 
575  return minIndex;
576 
577  }
578 
579 
581  {
582  return absolute4().maxAxis4();
583  }
584 
585 
586 
587 
595 /* void getValue(tf2Scalar *m) const
596  {
597  m[0] = m_floats[0];
598  m[1] = m_floats[1];
599  m[2] =m_floats[2];
600  }
601 */
608  TF2SIMD_FORCE_INLINE void setValue(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z,const tf2Scalar& w)
609  {
610  m_floats[0]=x;
611  m_floats[1]=y;
612  m_floats[2]=z;
613  m_floats[3]=w;
614  }
615 
616 
617 };
618 
619 
622 {
623  unsigned char* dest = (unsigned char*) &destVal;
624  const unsigned char* src = (const unsigned char*) &sourceVal;
625  dest[0] = src[7];
626  dest[1] = src[6];
627  dest[2] = src[5];
628  dest[3] = src[4];
629  dest[4] = src[3];
630  dest[5] = src[2];
631  dest[6] = src[1];
632  dest[7] = src[0];
633 }
635 TF2SIMD_FORCE_INLINE void tf2SwapVector3Endian(const Vector3& sourceVec, Vector3& destVec)
636 {
637  for (int i=0;i<4;i++)
638  {
639  tf2SwapScalarEndian(sourceVec[i],destVec[i]);
640  }
641 
642 }
643 
646 {
647 
648  Vector3 swappedVec;
649  for (int i=0;i<4;i++)
650  {
651  tf2SwapScalarEndian(vector[i],swappedVec[i]);
652  }
653  vector = swappedVec;
654 }
655 
656 TF2SIMD_FORCE_INLINE void tf2PlaneSpace1 (const Vector3& n, Vector3& p, Vector3& q)
657 {
658  if (tf2Fabs(n.z()) > TF2SIMDSQRT12) {
659  // choose p in y-z plane
660  tf2Scalar a = n[1]*n[1] + n[2]*n[2];
661  tf2Scalar k = tf2RecipSqrt (a);
662  p.setValue(0,-n[2]*k,n[1]*k);
663  // set q = n x p
664  q.setValue(a*k,-n[0]*p[2],n[0]*p[1]);
665  }
666  else {
667  // choose p in x-y plane
668  tf2Scalar a = n.x()*n.x() + n.y()*n.y();
669  tf2Scalar k = tf2RecipSqrt (a);
670  p.setValue(-n.y()*k,n.x()*k,0);
671  // set q = n x p
672  q.setValue(-n.z()*p.y(),n.z()*p.x(),a*k);
673  }
674 }
675 
676 
678 {
679  float m_floats[4];
680 };
681 
683 {
684  double m_floats[4];
685 
686 };
687 
688 TF2SIMD_FORCE_INLINE void Vector3::serializeFloat(struct Vector3FloatData& dataOut) const
689 {
691  for (int i=0;i<4;i++)
692  dataOut.m_floats[i] = float(m_floats[i]);
693 }
694 
695 TF2SIMD_FORCE_INLINE void Vector3::deSerializeFloat(const struct Vector3FloatData& dataIn)
696 {
697  for (int i=0;i<4;i++)
698  m_floats[i] = tf2Scalar(dataIn.m_floats[i]);
699 }
700 
701 
702 TF2SIMD_FORCE_INLINE void Vector3::serializeDouble(struct Vector3DoubleData& dataOut) const
703 {
705  for (int i=0;i<4;i++)
706  dataOut.m_floats[i] = double(m_floats[i]);
707 }
708 
709 TF2SIMD_FORCE_INLINE void Vector3::deSerializeDouble(const struct Vector3DoubleData& dataIn)
710 {
711  for (int i=0;i<4;i++)
712  m_floats[i] = tf2Scalar(dataIn.m_floats[i]);
713 }
714 
715 
716 TF2SIMD_FORCE_INLINE void Vector3::serialize(struct Vector3Data& dataOut) const
717 {
719  for (int i=0;i<4;i++)
720  dataOut.m_floats[i] = m_floats[i];
721 }
722 
723 TF2SIMD_FORCE_INLINE void Vector3::deSerialize(const struct Vector3Data& dataIn)
724 {
725  for (int i=0;i<4;i++)
726  m_floats[i] = dataIn.m_floats[i];
727 }
728 
729 }
730 
731 #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:621
tf2::tf2Vector4::tf2Vector4
TF2SIMD_FORCE_INLINE tf2Vector4(const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z, const tf2Scalar &w)
Definition: Vector3.h:498
tf2::dot
TF2SIMD_FORCE_INLINE tf2Scalar dot(const Quaternion &q1, const Quaternion &q2)
Calculate the dot product between two quaternions.
Definition: Quaternion.h:392
Scalar.h
tf2::Vector3FloatData::m_floats
float m_floats[4]
Definition: Vector3.h:679
tf2::tf2Vector4::closestAxis4
TF2SIMD_FORCE_INLINE int closestAxis4() const
Definition: Vector3.h:580
tf2::operator/
TF2SIMD_FORCE_INLINE Vector3 operator/(const Vector3 &v, const tf2Scalar &s)
Return the vector inversely scaled by s.
Definition: Vector3.h:395
tf2::tf2UnSwapVector3Endian
TF2SIMD_FORCE_INLINE void tf2UnSwapVector3Endian(Vector3 &vector)
tf2UnSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization
Definition: Vector3.h:645
TF2SIMD_EPSILON
#define TF2SIMD_EPSILON
Definition: Scalar.h:202
tf2::tf2Vector4::maxAxis4
TF2SIMD_FORCE_INLINE int maxAxis4() const
Definition: Vector3.h:519
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:410
tf2::tf2Vector4::minAxis4
TF2SIMD_FORCE_INLINE int minAxis4() const
Definition: Vector3.h:551
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:456
tf2::Vector3DoubleData
Definition: Vector3.h:682
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:608
tf2::tf2Vector4::tf2Vector4
TF2SIMD_FORCE_INLINE tf2Vector4()
Definition: Vector3.h:495
tf2Sqrt
TF2SIMD_FORCE_INLINE tf2Scalar tf2Sqrt(tf2Scalar x)
Definition: Scalar.h:177
MinMax.h
tf2::Vector3FloatData
Definition: Vector3.h:677
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:33
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:418
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:433
tf2::tf2Vector4::getW
tf2Scalar getW() const
Definition: Vector3.h:516
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:440
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:641
tf2::operator*
TF2SIMD_FORCE_INLINE Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)
Definition: Matrix3x3.h:603
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:635
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:656
tf2SetMin
TF2SIMD_FORCE_INLINE void tf2SetMin(T &a, const T &b)
Definition: MinMax.h:39
Vector3Data
#define Vector3Data
Definition: Vector3.h:27
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:446
tf2
Definition: buffer_core.h:54
tf2Fabs
TF2SIMD_FORCE_INLINE tf2Scalar tf2Fabs(tf2Scalar x)
Definition: Scalar.h:178
tf2::angle
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
Return the half angle between two quaternions.
Definition: Quaternion.h:407
tf2::operator+
TF2SIMD_FORCE_INLINE Vector3 operator+(const Vector3 &v1, const Vector3 &v2)
Return the sum of two vectors (Point symantics)
Definition: Vector3.h:354
tf2::tf2Vector4
Definition: Vector3.h:491
tf2::length
TF2SIMD_FORCE_INLINE tf2Scalar length(const Quaternion &q)
Return the length of a quaternion.
Definition: Quaternion.h:400
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:426
tf2::operator-
TF2SIMD_FORCE_INLINE Quaternion operator-(const Quaternion &q)
Return the negative of a quaternion.
Definition: Quaternion.h:356
TF2SIMDSQRT12
#define TF2SIMDSQRT12
Definition: Scalar.h:197
tf2SetMax
TF2SIMD_FORCE_INLINE void tf2SetMax(T &a, const T &b)
Definition: MinMax.h:48
serialize
void serialize(Stream &stream, const boost::array< T, N > &t)
tf2::tf2Vector4::absolute4
TF2SIMD_FORCE_INLINE tf2Vector4 absolute4() const
Definition: Vector3.h:505
tf2::Vector3DoubleData::m_floats
double m_floats[4]
Definition: Vector3.h:684


tf2
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sun Feb 4 2024 03:18:11