17#ifndef TF2__LINEARMATH__VECTOR3_HPP_
18#define TF2__LINEARMATH__VECTOR3_HPP_
29#define Vector3Data Vector3DoubleData
30#define Vector3DataName "Vector3DoubleData"
43#if defined (__SPU__) && defined (__CELLOS_LV2__)
95 m_floats[0] +=
v.
m_floats[0]; m_floats[1] +=
v.m_floats[1];m_floats[2] +=
v.m_floats[2];
104 m_floats[0] -=
v.
m_floats[0]; m_floats[1] -=
v.m_floats[1];m_floats[2] -=
v.m_floats[2];
111 m_floats[0] *=
s; m_floats[1] *=
s;m_floats[2] *=
s;
127 return m_floats[0] *
v.m_floats[0] + m_floats[1] *
v.m_floats[1] +m_floats[2] *
v.m_floats[2];
186 m_floats[1] *
v.m_floats[2] -m_floats[2] *
v.m_floats[1],
187 m_floats[2] *
v.m_floats[0] - m_floats[0] *
v.m_floats[2],
188 m_floats[0] *
v.m_floats[1] - m_floats[1] *
v.m_floats[0]);
193 return m_floats[0] * (
v1.m_floats[1] *
v2.m_floats[2] -
v1.m_floats[2] *
v2.m_floats[1]) +
194 m_floats[1] * (
v1.m_floats[2] *
v2.m_floats[0] -
v1.m_floats[0] *
v2.m_floats[2]) +
195 m_floats[2] * (
v1.m_floats[0] *
v2.m_floats[1] -
v1.m_floats[1] *
v2.m_floats[0]);
202 return m_floats[0] < m_floats[1] ? (m_floats[0] <m_floats[2] ? 0 : 2) : (m_floats[1] <m_floats[2] ? 1 : 2);
209 return m_floats[0] < m_floats[1] ? (m_floats[1] <m_floats[2] ? 2 : 1) : (m_floats[0] <m_floats[2] ? 2 : 0);
214 return absolute().minAxis();
219 return absolute().maxAxis();
225 m_floats[0] =
s *
v0.m_floats[0] +
rt *
v1.m_floats[0];
226 m_floats[1] =
s *
v0.m_floats[1] +
rt *
v1.m_floats[1];
227 m_floats[2] =
s *
v0.m_floats[2] +
rt *
v1.m_floats[2];
237 return Vector3(m_floats[0] + (
v.m_floats[0] - m_floats[0]) *
t,
238 m_floats[1] + (
v.m_floats[1] - m_floats[1]) *
t,
239 m_floats[2] + (
v.m_floats[2] -m_floats[2]) *
t);
246 m_floats[0] *=
v.
m_floats[0]; m_floats[1] *=
v.m_floats[1];m_floats[2] *=
v.m_floats[2];
281 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]));
286 return !(*
this ==
other);
321 v0->setValue(0. ,-z() ,y());
322 v1->setValue(z() ,0. ,-x());
323 v2->setValue(-y() ,x() ,0.);
343 return std::isnan(m_floats[0]) || std::isnan(m_floats[1]) || std::isnan(m_floats[2]);
364 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 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]);
378 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]);
384 return Vector3(-
v.m_floats[0], -
v.m_floats[1], -
v.m_floats[2]);
391 return Vector3(
v.m_floats[0] *
s,
v.m_floats[1] *
s,
v.m_floats[2] *
s);
413 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]);
428 return v1.distance2(
v2);
436 return v1.distance(
v2);
478 return (
v - *
this).length();
617 const unsigned char*
src =
reinterpret_cast<const unsigned char*
>(&
sourceVal);
630 for (
int i=0;
i<4;
i++)
642 for (
int i=0;
i<4;
i++)
655 p.setValue(0,-
n[2]*
k,
n[1]*
k);
657 q.setValue(
a*
k,-
n[0]*
p[2],
n[0]*
p[1]);
663 p.setValue(-
n.y()*
k,
n.x()*
k,0);
665 q.setValue(-
n.z()*
p.y(),
n.z()*
p.x(),
a*
k);
684 for (
int i=0;
i<4;
i++)
690 for (
int i=0;
i<4;
i++)
698 for (
int i=0;
i<4;
i++)
704 for (
int i=0;
i<4;
i++)
712 for (
int i=0;
i<4;
i++)
718 for (
int i=0;
i<4;
i++)
void tf2SetMax(T &a, const T &b)
Definition MinMax.hpp:50
void tf2SetMin(T &a, const T &b)
Definition MinMax.hpp:41
#define TF2_LARGE_FLOAT
Definition Scalar.hpp:161
tf2Scalar tf2Sqrt(tf2Scalar x)
Definition Scalar.hpp:177
#define TF2SIMDSQRT12
Definition Scalar.hpp:197
#define ATTRIBUTE_ALIGNED16(a)
Definition Scalar.hpp:134
#define TF2SIMD_EPSILON
Definition Scalar.hpp:202
tf2Scalar tf2Cos(tf2Scalar x)
Definition Scalar.hpp:179
#define tf2FullAssert(x)
Definition Scalar.hpp:148
#define TF2SIMD_FORCE_INLINE
Definition Scalar.hpp:129
#define tf2RecipSqrt(x)
Definition Scalar.hpp:199
tf2Scalar tf2Fabs(tf2Scalar x)
Definition Scalar.hpp:178
tf2Scalar tf2Acos(tf2Scalar x)
Definition Scalar.hpp:182
tf2Scalar tf2Sin(tf2Scalar x)
Definition Scalar.hpp:180
double tf2Scalar
The tf2Scalar type abstracts floating point numbers, to easily switch between double and single float...
Definition Scalar.hpp:159
#define Vector3Data
Definition Vector3.hpp:29
tf2::Vector3 can be used to represent 3D points and vectors. It has an un-used w component to suit 16...
Definition Vector3.hpp:40
bool fuzzyZero() const
Definition Vector3.hpp:337
Vector3 & operator*=(const tf2Scalar &s)
Scale the vector.
Definition Vector3.hpp:109
void setMax(const Vector3 &other)
Set each element to the max of the current values and the values of another Vector3.
Definition Vector3.hpp:292
Vector3(const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z)
Constructor from scalars.
Definition Vector3.hpp:82
tf2Scalar distance2(const Vector3 &v) const
Return the distance squared between the ends of this and another vector This is semantically treating...
Definition Vector3.hpp:471
Vector3 normalized() const
Return a normalized version of this vector.
Definition Vector3.hpp:481
tf2Scalar triple(const Vector3 &v1, const Vector3 &v2) const
Definition Vector3.hpp:191
tf2Scalar dot(const Vector3 &v) const
Return the dot product.
Definition Vector3.hpp:125
bool operator!=(const Vector3 &other) const
Definition Vector3.hpp:284
const tf2Scalar & getZ() const
Return the z value.
Definition Vector3.hpp:255
void setY(tf2Scalar y)
Set the y value.
Definition Vector3.hpp:259
const tf2Scalar & z() const
Return the z value.
Definition Vector3.hpp:269
const tf2Scalar & x() const
Return the x value.
Definition Vector3.hpp:265
Vector3 & normalize()
Normalize this vector x^2 + y^2 + z^2 = 1.
Definition Vector3.hpp:152
Vector3()
No initialization constructor.
Definition Vector3.hpp:73
Vector3 absolute() const
Return a vector will the absolute values of each element.
Definition Vector3.hpp:174
void deSerialize(const struct Vector3Data &dataIn)
Definition Vector3.hpp:716
int maxAxis() const
Return the axis with the largest value Note return values are 0,1,2 for x, y, or z.
Definition Vector3.hpp:207
void serialize(struct Vector3Data &dataOut) const
Definition Vector3.hpp:709
bool operator==(const Vector3 &other) const
Definition Vector3.hpp:279
Vector3 rotate(const Vector3 &wAxis, const tf2Scalar angle) const
Rotate this vector.
Definition Vector3.hpp:486
tf2Scalar length2() const
Return the length of the vector squared.
Definition Vector3.hpp:131
Vector3 lerp(const Vector3 &v, const tf2Scalar &t) const
Return the linear interpolation between this and another vector.
Definition Vector3.hpp:235
tf2Scalar distance(const Vector3 &v) const
Return the distance between the ends of this and another vector This is semantically treating the vec...
Definition Vector3.hpp:476
bool isZero() const
Definition Vector3.hpp:332
void setZero()
Definition Vector3.hpp:327
Vector3 & operator/=(const tf2Scalar &s)
Inversely scale the vector.
Definition Vector3.hpp:117
void serializeDouble(struct Vector3DoubleData &dataOut) const
Definition Vector3.hpp:695
void setX(tf2Scalar x)
Set the x value.
Definition Vector3.hpp:257
tf2Scalar m_floats[4]
Definition Vector3.hpp:66
Vector3 & operator*=(const Vector3 &v)
Elementwise multiply this vector by the other.
Definition Vector3.hpp:244
const tf2Scalar & getY() const
Return the y value.
Definition Vector3.hpp:253
tf2Scalar length() const
Return the length of the vector.
Definition Vector3.hpp:137
void setInterpolate3(const Vector3 &v0, const Vector3 &v1, tf2Scalar rt)
Definition Vector3.hpp:222
bool isnan() const
Definition Vector3.hpp:342
Vector3 & operator+=(const Vector3 &v)
Add a vector to this one.
Definition Vector3.hpp:92
int furthestAxis() const
Definition Vector3.hpp:212
void setZ(tf2Scalar z)
Set the z value.
Definition Vector3.hpp:261
Vector3 & operator-=(const Vector3 &v)
Subtract a vector from this one.
Definition Vector3.hpp:102
Vector3 cross(const Vector3 &v) const
Return the cross product between this and another vector.
Definition Vector3.hpp:183
void setValue(const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z)
Definition Vector3.hpp:310
int closestAxis() const
Definition Vector3.hpp:217
int minAxis() const
Return the axis with the smallest value Note return values are 0,1,2 for x, y, or z.
Definition Vector3.hpp:200
const tf2Scalar & getX() const
Return the x value.
Definition Vector3.hpp:251
void deSerializeDouble(const struct Vector3DoubleData &dataIn)
Definition Vector3.hpp:702
void deSerializeFloat(const struct Vector3FloatData &dataIn)
Definition Vector3.hpp:688
void setMin(const Vector3 &other)
Set each element to the min of the current values and the values of another Vector3.
Definition Vector3.hpp:302
tf2Scalar angle(const Vector3 &v) const
Return the angle between this and another vector.
Definition Vector3.hpp:167
const tf2Scalar & y() const
Return the y value.
Definition Vector3.hpp:267
void setW(tf2Scalar w)
Set the w value.
Definition Vector3.hpp:263
const tf2Scalar & w() const
Return the w value.
Definition Vector3.hpp:271
void getSkewSymmetricMatrix(Vector3 *v0, Vector3 *v1, Vector3 *v2) const
Definition Vector3.hpp:319
void serializeFloat(struct Vector3FloatData &dataOut) const
Definition Vector3.hpp:681
Definition Vector3.hpp:500
void setValue(const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z, const tf2Scalar &w)
Set the values.
Definition Vector3.hpp:601
tf2Vector4 absolute4() const
Definition Vector3.hpp:513
int minAxis4() const
Definition Vector3.hpp:560
int maxAxis4() const
Definition Vector3.hpp:528
tf2Vector4(const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z, const tf2Scalar &w)
Definition Vector3.hpp:506
int closestAxis4() const
Definition Vector3.hpp:589
tf2Vector4()
Definition Vector3.hpp:503
tf2Scalar getW() const
Definition Vector3.hpp:525
Definition buffer_core.hpp:58
tf2Scalar tf2Distance2(const Vector3 &v1, const Vector3 &v2)
Return the distance squared between two vectors.
Definition Vector3.hpp:426
void tf2SwapScalarEndian(const tf2Scalar &sourceVal, tf2Scalar &destVal)
tf2SwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization
Definition Vector3.hpp:614
Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)
Definition Matrix3x3.hpp:612
void tf2UnSwapVector3Endian(Vector3 &vector)
tf2UnSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization
Definition Vector3.hpp:638
void tf2PlaneSpace1(const Vector3 &n, Vector3 &p, Vector3 &q)
Definition Vector3.hpp:649
tf2Scalar tf2Triple(const Vector3 &v1, const Vector3 &v2, const Vector3 &v3)
Definition Vector3.hpp:454
void tf2SwapVector3Endian(const Vector3 &sourceVec, Vector3 &destVec)
tf2SwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization
Definition Vector3.hpp:628
tf2Scalar length(const Quaternion &q)
Return the length of a quaternion.
Definition Quaternion.hpp:464
tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
Return the half angle between two quaternions.
Definition Quaternion.hpp:471
B toMsg(const A &a)
Function that converts from one type to a ROS message type. It has to be implemented by each data typ...
tf2Scalar dot(const Quaternion &q1, const Quaternion &q2)
Calculate the dot product between two quaternions.
Definition Quaternion.hpp:456
tf2Scalar tf2Distance(const Vector3 &v1, const Vector3 &v2)
Return the distance between two vectors.
Definition Vector3.hpp:434
Vector3 operator+(const Vector3 &v1, const Vector3 &v2)
Return the sum of two vectors (Point symantics)
Definition Vector3.hpp:362
tf2Scalar tf2Dot(const Vector3 &v1, const Vector3 &v2)
Return the dot product between two vectors.
Definition Vector3.hpp:418
Quaternion operator-(const Quaternion &q)
Return the negative of a quaternion.
Definition Quaternion.hpp:420
Vector3 lerp(const Vector3 &v1, const Vector3 &v2, const tf2Scalar &t)
Return the linear interpolation between two vectors.
Definition Vector3.hpp:464
tf2Scalar tf2Angle(const Vector3 &v1, const Vector3 &v2)
Return the angle between two vectors.
Definition Vector3.hpp:441
Vector3 operator/(const Vector3 &v, const tf2Scalar &s)
Return the vector inversely scaled by s.
Definition Vector3.hpp:403
Vector3 tf2Cross(const Vector3 &v1, const Vector3 &v2)
Return the cross product of two vectors.
Definition Vector3.hpp:448
Definition Vector3.hpp:676
double m_floats[4]
Definition Vector3.hpp:677
Definition Vector3.hpp:671
float m_floats[4]
Definition Vector3.hpp:672
#define TF2_PUBLIC
Definition visibility_control.h:57