26 #define Vector3Data Vector3DoubleData 27 #define Vector3DataName "Vector3DoubleData" 42 #if defined (__SPU__) && defined (__CELLOS_LV2__) 47 return *((
const vec_float4*)&m_floats[0]);
50 #else //__CELLOS_LV2__ __SPU__ 51 #ifdef TF_USE_SSE // _WIN32 67 #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 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]);
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]);
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]);
420 return v1.distance2(v2);
428 return v1.distance(v2);
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 );
486 y = wAxis.cross( *
this );
488 return ( o + x *
tfCos( angle ) + y *
tfSin( 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)
541 maxVal = m_floats[3];
556 if (m_floats[0] < minVal)
559 minVal = m_floats[0];
561 if (m_floats[1] < minVal)
564 minVal = m_floats[1];
566 if (m_floats[2] < minVal)
571 if (m_floats[3] < minVal)
574 minVal = m_floats[3];
625 unsigned char* dest = (
unsigned char*) &destVal;
626 const unsigned char* src = (
const unsigned char*) &sourceVal;
639 for (
int i=0;i<4;i++)
651 for (
int i=0;i<4;i++)
664 p.setValue(0,-n[2]*k,n[1]*k);
666 q.setValue(a*k,-n[0]*p[2],n[0]*p[1]);
670 tfScalar a = n.x()*n.x() + n.y()*n.y();
672 p.setValue(-n.y()*k,n.x()*k,0);
674 q.setValue(-n.z()*p.y(),n.z()*p.x(),a*k);
693 for (
int i=0;i<4;i++)
694 dataOut.
m_floats[i] =
float(m_floats[i]);
699 for (
int i=0;i<4;i++)
707 for (
int i=0;i<4;i++)
708 dataOut.
m_floats[i] =
double(m_floats[i]);
713 for (
int i=0;i<4;i++)
721 for (
int i=0;i<4;i++)
722 dataOut.m_floats[i] = m_floats[i];
727 for (
int i=0;i<4;i++)
728 m_floats[i] = dataIn.m_floats[i];
733 #endif //TFSIMD__VECTOR3_H TFSIMD_FORCE_INLINE Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)
TFSIMD_FORCE_INLINE Quaternion operator-(const Quaternion &q)
Return the negative of a quaternion.
double tfScalar
The tfScalar type abstracts floating point numbers, to easily switch between double and single floati...
TFSIMD_FORCE_INLINE bool operator==(const Matrix3x3 &m1, const Matrix3x3 &m2)
Equality operator between two matrices It will test all elements are equal.
TFSIMD_FORCE_INLINE Vector3 operator/(const Vector3 &v, const tfScalar &s)
Return the vector inversely scaled by s.
TFSIMD_FORCE_INLINE tfScalar tfDistance2(const Vector3 &v1, const Vector3 &v2)
Return the distance squared between two vectors.
TFSIMD_FORCE_INLINE tfScalar tfTriple(const Vector3 &v1, const Vector3 &v2, const Vector3 &v3)
TFSIMD_FORCE_INLINE tfScalar tfDistance(const Vector3 &v1, const Vector3 &v2)
Return the distance between two vectors.
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
Return the half angle between two quaternions.
TFSIMD_FORCE_INLINE int maxAxis4() const
TFSIMD_FORCE_INLINE void tfPlaneSpace1(const Vector3 &n, Vector3 &p, Vector3 &q)
TFSIMD_FORCE_INLINE tfScalar tfCos(tfScalar x)
TFSIMD_FORCE_INLINE tfScalar tfAcos(tfScalar x)
void serialize(Stream &stream, const T &t)
TFSIMD_FORCE_INLINE tfVector4()
TFSIMD_FORCE_INLINE void tfSwapScalarEndian(const tfScalar &sourceVal, tfScalar &destVal)
tfSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization ...
TFSIMD_FORCE_INLINE tfScalar tfDot(const Vector3 &v1, const Vector3 &v2)
Return the dot product between two vectors.
TFSIMD_FORCE_INLINE void tfSetMin(T &a, const T &b)
TFSIMD_FORCE_INLINE int minAxis4() const
TFSIMD_FORCE_INLINE void setValue(const tfScalar &x, const tfScalar &y, const tfScalar &z, const tfScalar &w)
Set x,y,z and zero w.
TFSIMD_FORCE_INLINE Vector3 lerp(const Vector3 &v1, const Vector3 &v2, const tfScalar &t)
Return the linear interpolation between two vectors.
TFSIMD_FORCE_INLINE Vector3 tfCross(const Vector3 &v1, const Vector3 &v2)
Return the cross product of two vectors.
#define TFSIMD_FORCE_INLINE
TFSIMD_FORCE_INLINE tfVector4 absolute4() const
TFSIMD_FORCE_INLINE void tfSwapVector3Endian(const Vector3 &sourceVec, Vector3 &destVec)
tfSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization ...
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
Calculate the dot product between two quaternions.
TFSIMD_FORCE_INLINE tfScalar tfAngle(const Vector3 &v1, const Vector3 &v2)
Return the angle between two vectors.
TFSIMD_FORCE_INLINE tfScalar tfSqrt(tfScalar x)
TFSIMD_FORCE_INLINE tfVector4(const tfScalar &x, const tfScalar &y, const tfScalar &z, const tfScalar &w)
TFSIMD_FORCE_INLINE Vector3 operator+(const Vector3 &v1, const Vector3 &v2)
Return the sum of two vectors (Point symantics)
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.
TFSIMD_FORCE_INLINE tfScalar tfSin(tfScalar x)
TFSIMD_FORCE_INLINE void tfUnSwapVector3Endian(Vector3 &vector)
tfUnSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization ...
TFSIMD_FORCE_INLINE int closestAxis4() const
TFSIMD_FORCE_INLINE tfScalar tfFabs(tfScalar x)
ATTRIBUTE_ALIGNED16(class) QuadWord
The QuadWord class is base class for Vector3 and Quaternion. Some issues under PS3 Linux with IBM 2...
TFSIMD_FORCE_INLINE void tfSetMax(T &a, const T &b)