27 #define Vector3Data Vector3DoubleData 28 #define Vector3DataName "Vector3DoubleData" 41 #if defined (__SPU__) && defined (__CELLOS_LV2__) 46 return *((
const vec_float4*)&m_floats[0]);
49 #else //__CELLOS_LV2__ __SPU__ 50 #ifdef TF2_USE_SSE // _WIN32 66 #endif //__CELLOS_LV2__ __SPU__ 93 m_floats[0] += v.m_floats[0]; m_floats[1] += v.m_floats[1];m_floats[2] += v.m_floats[2];
102 m_floats[0] -= v.m_floats[0]; m_floats[1] -= v.m_floats[1];m_floats[2] -= v.m_floats[2];
109 m_floats[0] *= s; m_floats[1] *= s;m_floats[2] *= s;
125 return m_floats[0] * v.m_floats[0] + m_floats[1] * v.m_floats[1] +m_floats[2] * v.m_floats[2];
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]);
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]);
200 return m_floats[0] < m_floats[1] ? (m_floats[0] <m_floats[2] ? 0 : 2) : (m_floats[1] <m_floats[2] ? 1 : 2);
207 return m_floats[0] < m_floats[1] ? (m_floats[1] <m_floats[2] ? 2 : 1) : (m_floats[0] <m_floats[2] ? 2 : 0);
212 return absolute().minAxis();
217 return absolute().maxAxis();
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];
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);
244 m_floats[0] *= v.m_floats[0]; m_floats[1] *= v.m_floats[1];m_floats[2] *= v.m_floats[2];
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]));
284 return !(*
this == other);
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]);
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]);
316 void getSkewSymmetricMatrix(Vector3* v0,Vector3* v1,Vector3* v2)
const 318 v0->setValue(0. ,-z() ,y());
319 v1->setValue(z() ,0. ,-x());
320 v2->setValue(-y() ,x() ,0.);
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]);
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]);
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]);
376 return Vector3(-v.m_floats[0], -v.m_floats[1], -v.m_floats[2]);
383 return Vector3(v.m_floats[0] * s, v.m_floats[1] * s, v.m_floats[2] * s);
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]);
410 tf2Dot(
const Vector3& v1,
const Vector3& v2)
420 return v1.distance2(v2);
428 return v1.distance(v2);
446 tf2Triple(
const Vector3& v1,
const Vector3& v2,
const Vector3& v3)
448 return v1.triple(v2, v3);
458 return v1.lerp(v2, t);
465 return (v - *
this).length2();
470 return (v - *
this).length();
482 Vector3 o = wAxis * wAxis.dot( *
this );
483 Vector3 x = *
this - o;
486 y = wAxis.cross( *
this );
488 return ( o + x *
tf2Cos( angle ) + y *
tf2Sin( angle ) );
523 if (m_floats[0] > maxVal)
526 maxVal = m_floats[0];
528 if (m_floats[1] > maxVal)
531 maxVal = m_floats[1];
533 if (m_floats[2] > maxVal)
538 if (m_floats[3] > maxVal)
555 if (m_floats[0] < minVal)
558 minVal = m_floats[0];
560 if (m_floats[1] < minVal)
563 minVal = m_floats[1];
565 if (m_floats[2] < minVal)
570 if (m_floats[3] < minVal)
623 unsigned char* dest = (
unsigned char*) &destVal;
624 const unsigned char* src = (
const unsigned char*) &sourceVal;
637 for (
int i=0;i<4;i++)
649 for (
int i=0;i<4;i++)
662 p.setValue(0,-n[2]*k,n[1]*k);
664 q.setValue(a*k,-n[0]*p[2],n[0]*p[1]);
670 p.setValue(-n.y()*k,n.x()*k,0);
672 q.setValue(-n.z()*p.y(),n.z()*p.x(),a*k);
691 for (
int i=0;i<4;i++)
692 dataOut.
m_floats[i] =
float(m_floats[i]);
697 for (
int i=0;i<4;i++)
705 for (
int i=0;i<4;i++)
706 dataOut.
m_floats[i] =
double(m_floats[i]);
711 for (
int i=0;i<4;i++)
719 for (
int i=0;i<4;i++)
720 dataOut.m_floats[i] = m_floats[i];
725 for (
int i=0;i<4;i++)
726 m_floats[i] = dataIn.m_floats[i];
731 #endif //TF2_VECTOR3_H #define TF2SIMD_FORCE_INLINE
TF2SIMD_FORCE_INLINE tf2Scalar tf2Angle(const Vector3 &v1, const Vector3 &v2)
Return the angle between two vectors.
TF2SIMD_FORCE_INLINE bool operator==(const Matrix3x3 &m1, const Matrix3x3 &m2)
Equality operator between two matrices It will test all elements are equal.
TF2SIMD_FORCE_INLINE tf2Scalar tf2Cos(tf2Scalar x)
TF2SIMD_FORCE_INLINE tf2Vector4 absolute4() const
TF2SIMD_FORCE_INLINE tf2Scalar tf2Acos(tf2Scalar x)
TF2SIMD_FORCE_INLINE int closestAxis4() const
TF2SIMD_FORCE_INLINE void setValue(const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z, const tf2Scalar &w)
Set x,y,z and zero w.
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
Return the half angle between two quaternions.
TF2SIMD_FORCE_INLINE tf2Vector4(const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z, const tf2Scalar &w)
TF2SIMD_FORCE_INLINE int minAxis4() const
double tf2Scalar
The tf2Scalar type abstracts floating point numbers, to easily switch between double and single float...
TF2SIMD_FORCE_INLINE tf2Scalar tf2Fabs(tf2Scalar x)
TF2SIMD_FORCE_INLINE tf2Scalar dot(const Quaternion &q1, const Quaternion &q2)
Calculate the dot product between two quaternions.
TF2SIMD_FORCE_INLINE tf2Scalar tf2Dot(const Vector3 &v1, const Vector3 &v2)
Return the dot product between two vectors.
TF2SIMD_FORCE_INLINE void tf2PlaneSpace1(const Vector3 &n, Vector3 &p, Vector3 &q)
TF2SIMD_FORCE_INLINE tf2Scalar tf2Distance2(const Vector3 &v1, const Vector3 &v2)
Return the distance squared between two vectors.
TF2SIMD_FORCE_INLINE int maxAxis4() const
ATTRIBUTE_ALIGNED16(class) QuadWord
The QuadWord class is base class for Vector3 and Quaternion. Some issues under PS3 Linux with IBM 2...
TF2SIMD_FORCE_INLINE tf2Vector4()
TF2SIMD_FORCE_INLINE void tf2SwapVector3Endian(const Vector3 &sourceVec, Vector3 &destVec)
tf2SwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization ...
TF2SIMD_FORCE_INLINE tf2Scalar length(const Quaternion &q)
Return the length of a quaternion.
TF2SIMD_FORCE_INLINE Vector3 lerp(const Vector3 &v1, const Vector3 &v2, const tf2Scalar &t)
Return the linear interpolation between two vectors.
void serialize(Stream &stream, const T &t)
TF2SIMD_FORCE_INLINE void tf2SetMax(T &a, const T &b)
TF2SIMD_FORCE_INLINE void tf2UnSwapVector3Endian(Vector3 &vector)
tf2UnSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization ...
TF2SIMD_FORCE_INLINE Vector3 operator+(const Vector3 &v1, const Vector3 &v2)
Return the sum of two vectors (Point symantics)
TF2SIMD_FORCE_INLINE tf2Scalar tf2Sin(tf2Scalar x)
TF2SIMD_FORCE_INLINE tf2Scalar tf2Sqrt(tf2Scalar x)
TF2SIMD_FORCE_INLINE Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)
TF2SIMD_FORCE_INLINE tf2Scalar tf2Distance(const Vector3 &v1, const Vector3 &v2)
Return the distance between two vectors.
TF2SIMD_FORCE_INLINE Quaternion operator-(const Quaternion &q)
Return the negative of a quaternion.
TF2SIMD_FORCE_INLINE Vector3 operator/(const Vector3 &v, const tf2Scalar &s)
Return the vector inversely scaled by s.
TF2SIMD_FORCE_INLINE Vector3 tf2Cross(const Vector3 &v1, const Vector3 &v2)
Return the cross product of two vectors.
TF2SIMD_FORCE_INLINE tf2Scalar tf2Triple(const Vector3 &v1, const Vector3 &v2, const Vector3 &v3)
TF2SIMD_FORCE_INLINE void tf2SwapScalarEndian(const tf2Scalar &sourceVal, tf2Scalar &destVal)
tf2SwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization ...
TF2SIMD_FORCE_INLINE void tf2SetMin(T &a, const T &b)