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__ 109 m_floats[0] *= s; m_floats[1] *= s;m_floats[2] *= s;
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);
236 m_floats[1] + (v.
m_floats[1] - m_floats[1]) * t,
237 m_floats[2] + (v.
m_floats[2] -m_floats[2]) * t);
284 return !(*
this == other);
458 return v1.
lerp(v2, t);
465 return (v - *
this).length2();
470 return (v - *
this).length();
486 y = wAxis.cross( *
this );
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];
584 return absolute4().maxAxis4();
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++)
666 q.
setValue(a*k,-n[0]*p[2],n[0]*p[1]);
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 Vector3 &v)
Add a vector to this one.
TFSIMD_FORCE_INLINE void setMin(const Vector3 &other)
Set each element to the min of the current values and the values of another Vector3.
TFSIMD_FORCE_INLINE Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)
TFSIMD_FORCE_INLINE void setW(tfScalar w)
Set the w value.
TFSIMD_FORCE_INLINE Quaternion operator-(const Quaternion &q)
Return the negative of a quaternion.
TFSIMD_FORCE_INLINE void serialize(struct Vector3Data &dataOut) const
void getSkewSymmetricMatrix(Vector3 *v0, Vector3 *v1, Vector3 *v2) const
TFSIMD_FORCE_INLINE void setX(tfScalar x)
Set the x value.
TFSIMD_FORCE_INLINE bool fuzzyZero() const
TFSIMD_FORCE_INLINE void setY(tfScalar y)
Set the y value.
double tfScalar
The tfScalar type abstracts floating point numbers, to easily switch between double and single floati...
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 int maxAxis() const
Return the axis with the largest value Note return values are 0,1,2 for x, y, or z.
TFSIMD_FORCE_INLINE void setZ(tfScalar z)
Set the z value.
TFSIMD_FORCE_INLINE bool isZero() const
TFSIMD_FORCE_INLINE tfScalar tfTriple(const Vector3 &v1, const Vector3 &v2, const Vector3 &v3)
TFSIMD_FORCE_INLINE const tfScalar & getY() const
Return the y value.
TFSIMD_FORCE_INLINE tfVector4 absolute4() const
TFSIMD_FORCE_INLINE tfScalar angle(const Vector3 &v) const
Return the angle between this and another vector.
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
Return the distance between the ends of this and another vector This is symantically treating the vec...
TFSIMD_FORCE_INLINE tfScalar tfDistance(const Vector3 &v1, const Vector3 &v2)
Return the distance between two vectors.
TFSIMD_FORCE_INLINE void serializeDouble(struct Vector3DoubleData &dataOut) const
TFSIMD_FORCE_INLINE const tfScalar & getZ() const
Return the z value.
TFSIMD_FORCE_INLINE void setValue(const tfScalar &x, const tfScalar &y, const tfScalar &z)
TFSIMD_FORCE_INLINE Vector3 cross(const Vector3 &v) const
Return the cross product between this and another vector.
TFSIMD_FORCE_INLINE bool operator!=(const Vector3 &other) const
TFSIMD_FORCE_INLINE void setMax(const Vector3 &other)
Set each element to the max of the current values and the values of another Vector3.
TFSIMD_FORCE_INLINE Vector3 lerp(const Vector3 &v, const tfScalar &t) const
Return the linear interpolation between this and another vector.
TFSIMD_FORCE_INLINE const tfScalar & x() const
Return the x value.
TFSIMD_FORCE_INLINE void tfPlaneSpace1(const Vector3 &n, Vector3 &p, Vector3 &q)
TFSIMD_FORCE_INLINE Vector3()
No initialization constructor.
TFSIMD_FORCE_INLINE tfScalar tfCos(tfScalar x)
TFSIMD_FORCE_INLINE tfScalar triple(const Vector3 &v1, const Vector3 &v2) const
TFSIMD_FORCE_INLINE tfScalar dot(const Vector3 &v) const
Return the dot product.
TFSIMD_FORCE_INLINE void serializeFloat(struct Vector3FloatData &dataOut) const
TFSIMD_FORCE_INLINE Vector3 rotate(const Vector3 &wAxis, const tfScalar angle) const
Rotate this vector.
TFSIMD_FORCE_INLINE tfScalar distance2(const Vector3 &v) const
Return the distance squared between the ends of this and another vector This is symantically treating...
TFSIMD_FORCE_INLINE int minAxis() const
Return the axis with the smallest value Note return values are 0,1,2 for x, y, or z...
TFSIMD_FORCE_INLINE tfScalar tfAcos(tfScalar x)
TFSIMD_FORCE_INLINE const tfScalar & z() const
Return the z value.
TFSIMD_FORCE_INLINE void setInterpolate3(const Vector3 &v0, const Vector3 &v1, tfScalar rt)
TFSIMD_FORCE_INLINE void deSerializeDouble(const struct Vector3DoubleData &dataIn)
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 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 normalized() const
Return a normalized version of this vector.
TFSIMD_FORCE_INLINE Vector3 tfCross(const Vector3 &v1, const Vector3 &v2)
Return the cross product of two vectors.
TFSIMD_FORCE_INLINE const tfScalar & y() const
Return the y value.
#define TFSIMD_FORCE_INLINE
TFSIMD_FORCE_INLINE Vector3(const tfScalar &x, const tfScalar &y, const tfScalar &z)
Constructor from scalars.
TFSIMD_FORCE_INLINE void tfSwapVector3Endian(const Vector3 &sourceVec, Vector3 &destVec)
tfSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization ...
TFSIMD_FORCE_INLINE int closestAxis() const
TFSIMD_FORCE_INLINE const tfScalar & w() const
Return the w value.
TFSIMD_FORCE_INLINE int closestAxis4() const
TFSIMD_FORCE_INLINE Vector3 & operator-=(const Vector3 &v)
Sutfract a vector from this one.
TFSIMD_FORCE_INLINE Vector3 & normalize()
Normalize this vector x^2 + y^2 + z^2 = 1.
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 Vector3 absolute() const
Return a vector will the absolute values of each element.
TFSIMD_FORCE_INLINE int maxAxis4() const
TFSIMD_FORCE_INLINE bool operator==(const Vector3 &other) const
TFSIMD_FORCE_INLINE Vector3 operator+(const Vector3 &v1, const Vector3 &v2)
Return the sum of two vectors (Point symantics)
TFSIMD_FORCE_INLINE int furthestAxis() const
TFSIMD_FORCE_INLINE int minAxis4() const
TFSIMD_FORCE_INLINE const tfScalar & getX() const
Return the x value.
TFSIMD_FORCE_INLINE Vector3 & operator/=(const tfScalar &s)
Inversely scale the vector.
TFSIMD_FORCE_INLINE void deSerialize(const struct Vector3Data &dataIn)
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 tfScalar tfFabs(tfScalar x)
TFSIMD_FORCE_INLINE Vector3 & operator*=(const Vector3 &v)
Elementwise multiply this vector by the other.
TFSIMD_FORCE_INLINE void tfSetMax(T &a, const T &b)
TFSIMD_FORCE_INLINE void deSerializeFloat(const struct Vector3FloatData &dataIn)
TFSIMD_FORCE_INLINE tfScalar length2() const
Return the length of the vector squared.
TFSIMD_FORCE_INLINE Vector3 & operator*=(const tfScalar &s)
Scale the vector.
TFSIMD_FORCE_INLINE tfScalar length() const
Return the length of the vector.
Vector3 can be used to represent 3D points and vectors. It has an un-used w component to suit 16-byte...
tf::tfVector4 __attribute__