tf2 rolling
tf2 maintains the relationship between coordinate frames in a tree structure buffered in time, and lets the user transform points, vectors, etc between any two coordinate frames at any desired point in time.
Loading...
Searching...
No Matches
Vector3.hpp
Go to the documentation of this file.
1/*
2Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/
3
4This software is provided 'as-is', without any express or implied warranty.
5In no event will the authors be held liable for any damages arising from the use of this software.
6Permission is granted to anyone to use this software for any purpose,
7including commercial applications, and to alter it and redistribute it freely,
8subject to the following restrictions:
9
101. 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.
112. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
123. This notice may not be removed or altered from any source distribution.
13*/
14
15
16
17#ifndef TF2__LINEARMATH__VECTOR3_HPP_
18#define TF2__LINEARMATH__VECTOR3_HPP_
19
20#include <cmath>
21
22#include "Scalar.hpp"
23#include "MinMax.hpp"
25
26namespace tf2
27{
28
29#define Vector3Data Vector3DoubleData
30#define Vector3DataName "Vector3DoubleData"
31
32
33
34
40{
41public:
42
43#if defined (__SPU__) && defined (__CELLOS_LV2__)
44 tf2Scalar m_floats[4];
45public:
47 {
48 return *((const vec_float4*)&m_floats[0]);
49 }
50public:
51#else //__CELLOS_LV2__ __SPU__
52#ifdef TF2_USE_SSE // _WIN32
53 union {
55 tf2Scalar m_floats[4];
56 };
58 {
59 return mVec128;
60 }
62 {
63 mVec128 = v128;
64 }
65#else
66 tf2Scalar m_floats[4];
67#endif
68#endif //__CELLOS_LV2__ __SPU__
69
70 public:
71
74
75
76
83 {
84 m_floats[0] = x;
85 m_floats[1] = y;
86 m_floats[2] = z;
87 m_floats[3] = tf2Scalar(0.);
88 }
89
93 {
94
95 m_floats[0] += v.m_floats[0]; m_floats[1] += v.m_floats[1];m_floats[2] += v.m_floats[2];
96 return *this;
97 }
98
99
103 {
104 m_floats[0] -= v.m_floats[0]; m_floats[1] -= v.m_floats[1];m_floats[2] -= v.m_floats[2];
105 return *this;
106 }
110 {
111 m_floats[0] *= s; m_floats[1] *= s;m_floats[2] *= s;
112 return *this;
113 }
114
118 {
119 tf2FullAssert(s != tf2Scalar(0.0));
120 return *this *= tf2Scalar(1.0) / s;
121 }
122
126 {
127 return m_floats[0] * v.m_floats[0] + m_floats[1] * v.m_floats[1] +m_floats[2] * v.m_floats[2];
128 }
129
132 {
133 return dot(*this);
134 }
135
138 {
139 return tf2Sqrt(length2());
140 }
141
144 TF2SIMD_FORCE_INLINE tf2Scalar distance2(const Vector3& v) const;
145
148 TF2SIMD_FORCE_INLINE tf2Scalar distance(const Vector3& v) const;
149
153 {
154 return *this /= length();
155 }
156
158 TF2SIMD_FORCE_INLINE Vector3 normalized() const;
159
163 TF2SIMD_FORCE_INLINE Vector3 rotate( const Vector3& wAxis, const tf2Scalar angle ) const;
164
168 {
169 tf2Scalar s = tf2Sqrt(length2() * v.length2());
170 tf2FullAssert(s != tf2Scalar(0.0));
171 return tf2Acos(dot(v) / s);
172 }
175 {
176 return Vector3(
177 tf2Fabs(m_floats[0]),
178 tf2Fabs(m_floats[1]),
179 tf2Fabs(m_floats[2]));
180 }
184 {
185 return Vector3(
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]);
189 }
190
192 {
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]);
196 }
197
201 {
202 return m_floats[0] < m_floats[1] ? (m_floats[0] <m_floats[2] ? 0 : 2) : (m_floats[1] <m_floats[2] ? 1 : 2);
203 }
204
208 {
209 return m_floats[0] < m_floats[1] ? (m_floats[1] <m_floats[2] ? 2 : 1) : (m_floats[0] <m_floats[2] ? 2 : 0);
210 }
211
213 {
214 return absolute().minAxis();
215 }
216
218 {
219 return absolute().maxAxis();
220 }
221
223 {
224 tf2Scalar s = tf2Scalar(1.0) - rt;
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];
228 //don't do the unused w component
229 // m_co[3] = s * v0[3] + rt * v1[3];
230 }
231
236 {
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);
240 }
241
245 {
246 m_floats[0] *= v.m_floats[0]; m_floats[1] *= v.m_floats[1];m_floats[2] *= v.m_floats[2];
247 return *this;
248 }
249
251 TF2SIMD_FORCE_INLINE const tf2Scalar& getX() const { return m_floats[0]; }
253 TF2SIMD_FORCE_INLINE const tf2Scalar& getY() const { return m_floats[1]; }
255 TF2SIMD_FORCE_INLINE const tf2Scalar& getZ() const { return m_floats[2]; }
257 TF2SIMD_FORCE_INLINE void setX(tf2Scalar x) { m_floats[0] = x;};
259 TF2SIMD_FORCE_INLINE void setY(tf2Scalar y) { m_floats[1] = y;};
261 TF2SIMD_FORCE_INLINE void setZ(tf2Scalar z) {m_floats[2] = z;};
263 TF2SIMD_FORCE_INLINE void setW(tf2Scalar w) { m_floats[3] = w;};
265 TF2SIMD_FORCE_INLINE const tf2Scalar& x() const { return m_floats[0]; }
267 TF2SIMD_FORCE_INLINE const tf2Scalar& y() const { return m_floats[1]; }
269 TF2SIMD_FORCE_INLINE const tf2Scalar& z() const { return m_floats[2]; }
271 TF2SIMD_FORCE_INLINE const tf2Scalar& w() const { return m_floats[3]; }
272
273 //TF2SIMD_FORCE_INLINE tf2Scalar& operator[](int i) { return (&m_floats[0])[i]; }
274 //TF2SIMD_FORCE_INLINE const tf2Scalar& operator[](int i) const { return (&m_floats[0])[i]; }
276 TF2SIMD_FORCE_INLINE operator tf2Scalar *() { return &m_floats[0]; }
277 TF2SIMD_FORCE_INLINE operator const tf2Scalar *() const { return &m_floats[0]; }
278
280 {
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]));
282 }
283
285 {
286 return !(*this == other);
287 }
288
293 {
294 tf2SetMax(m_floats[0], other.m_floats[0]);
295 tf2SetMax(m_floats[1], other.m_floats[1]);
296 tf2SetMax(m_floats[2], other.m_floats[2]);
297 tf2SetMax(m_floats[3], other.w());
298 }
303 {
304 tf2SetMin(m_floats[0], other.m_floats[0]);
305 tf2SetMin(m_floats[1], other.m_floats[1]);
306 tf2SetMin(m_floats[2], other.m_floats[2]);
307 tf2SetMin(m_floats[3], other.w());
308 }
309
310 TF2SIMD_FORCE_INLINE void setValue(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z)
311 {
312 m_floats[0]=x;
313 m_floats[1]=y;
314 m_floats[2]=z;
315 m_floats[3] = tf2Scalar(0.);
316 }
317
320 {
321 v0->setValue(0. ,-z() ,y());
322 v1->setValue(z() ,0. ,-x());
323 v2->setValue(-y() ,x() ,0.);
324 }
325
327 void setZero()
328 {
329 setValue(tf2Scalar(0.),tf2Scalar(0.),tf2Scalar(0.));
330 }
331
333 {
334 return m_floats[0] == tf2Scalar(0) && m_floats[1] == tf2Scalar(0) && m_floats[2] == tf2Scalar(0);
335 }
336
338 {
339 return length2() < TF2SIMD_EPSILON;
340 }
341
343 return std::isnan(m_floats[0]) || std::isnan(m_floats[1]) || std::isnan(m_floats[2]);
344 }
345
346 TF2SIMD_FORCE_INLINE void serialize(struct Vector3Data& dataOut) const;
347
348 TF2SIMD_FORCE_INLINE void deSerialize(const struct Vector3Data& dataIn);
349
350 TF2SIMD_FORCE_INLINE void serializeFloat(struct Vector3FloatData& dataOut) const;
351
352 TF2SIMD_FORCE_INLINE void deSerializeFloat(const struct Vector3FloatData& dataIn);
353
354 TF2SIMD_FORCE_INLINE void serializeDouble(struct Vector3DoubleData& dataOut) const;
355
356 TF2SIMD_FORCE_INLINE void deSerializeDouble(const struct Vector3DoubleData& dataIn);
357
358};
359
362operator+(const Vector3& v1, const Vector3& v2)
363{
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]);
365}
366
369operator*(const Vector3& v1, const Vector3& v2)
370{
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]);
372}
373
377{
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]);
379}
383{
384 return Vector3(-v.m_floats[0], -v.m_floats[1], -v.m_floats[2]);
385}
386
390{
391 return Vector3(v.m_floats[0] * s, v.m_floats[1] * s, v.m_floats[2] * s);
392}
393
397{
398 return v * s;
399}
400
404{
405 tf2FullAssert(s != tf2Scalar(0.0));
406 return v * (tf2Scalar(1.0) / s);
407}
408
412{
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]);
414}
415
418tf2Dot(const Vector3& v1, const Vector3& v2)
419{
420 return v1.dot(v2);
421}
422
423
427{
428 return v1.distance2(v2);
429}
430
431
435{
436 return v1.distance(v2);
437}
438
441tf2Angle(const Vector3& v1, const Vector3& v2)
442{
443 return v1.angle(v2);
444}
445
448tf2Cross(const Vector3& v1, const Vector3& v2)
449{
450 return v1.cross(v2);
451}
452
454tf2Triple(const Vector3& v1, const Vector3& v2, const Vector3& v3)
455{
456 return v1.triple(v2, v3);
457}
458
464lerp(const Vector3& v1, const Vector3& v2, const tf2Scalar& t)
465{
466 return v1.lerp(v2, t);
467}
468
469
470
472{
473 return (v - *this).length2();
474}
475
477{
478 return (v - *this).length();
479}
480
482{
483 return *this / length();
484}
485
487{
488 // wAxis must be a unit lenght vector
489
490 Vector3 o = wAxis * wAxis.dot( *this );
491 Vector3 x = *this - o;
492 Vector3 y;
493
494 y = wAxis.cross( *this );
495
496 return ( o + x * tf2Cos( angle ) + y * tf2Sin( angle ) );
497}
498
499class tf2Vector4 : public Vector3
500{
501public:
502
504
505
507 : Vector3(x,y,z)
508 {
509 m_floats[3] = w;
510 }
511
512
514 {
515 return tf2Vector4(
516 tf2Fabs(m_floats[0]),
517 tf2Fabs(m_floats[1]),
518 tf2Fabs(m_floats[2]),
519 tf2Fabs(m_floats[3]));
520 }
521
522
523
525 tf2Scalar getW() const { return m_floats[3];}
526
527
529 {
530 int maxIndex = -1;
532 if (m_floats[0] > maxVal)
533 {
534 maxIndex = 0;
535 maxVal = m_floats[0];
536 }
537 if (m_floats[1] > maxVal)
538 {
539 maxIndex = 1;
540 maxVal = m_floats[1];
541 }
542 if (m_floats[2] > maxVal)
543 {
544 maxIndex = 2;
545 maxVal =m_floats[2];
546 }
547 if (m_floats[3] > maxVal)
548 {
549 maxIndex = 3;
550 }
551
552
553
554
555 return maxIndex;
556
557 }
558
559
561 {
562 int minIndex = -1;
564 if (m_floats[0] < minVal)
565 {
566 minIndex = 0;
567 minVal = m_floats[0];
568 }
569 if (m_floats[1] < minVal)
570 {
571 minIndex = 1;
572 minVal = m_floats[1];
573 }
574 if (m_floats[2] < minVal)
575 {
576 minIndex = 2;
577 minVal =m_floats[2];
578 }
579 if (m_floats[3] < minVal)
580 {
581 minIndex = 3;
582 }
583
584 return minIndex;
585
586 }
587
588
590 {
591 return absolute4().maxAxis4();
592 }
593
594
602 {
603 m_floats[0]=x;
604 m_floats[1]=y;
605 m_floats[2]=z;
606 m_floats[3]=w;
607 }
608
609
610};
611
612
615{
616 unsigned char* dest = (unsigned char*) &destVal;
617 const unsigned char* src = reinterpret_cast<const unsigned char*>(&sourceVal);
618 dest[0] = src[7];
619 dest[1] = src[6];
620 dest[2] = src[5];
621 dest[3] = src[4];
622 dest[4] = src[3];
623 dest[5] = src[2];
624 dest[6] = src[1];
625 dest[7] = src[0];
626}
629{
630 for (int i=0;i<4;i++)
631 {
633 }
634
635}
636
639{
640
642 for (int i=0;i<4;i++)
643 {
645 }
647}
648
650{
651 if (tf2Fabs(n.z()) > TF2SIMDSQRT12) {
652 // choose p in y-z plane
653 tf2Scalar a = n[1]*n[1] + n[2]*n[2];
655 p.setValue(0,-n[2]*k,n[1]*k);
656 // set q = n x p
657 q.setValue(a*k,-n[0]*p[2],n[0]*p[1]);
658 }
659 else {
660 // choose p in x-y plane
661 tf2Scalar a = n.x()*n.x() + n.y()*n.y();
663 p.setValue(-n.y()*k,n.x()*k,0);
664 // set q = n x p
665 q.setValue(-n.z()*p.y(),n.z()*p.x(),a*k);
666 }
667}
668
669
671{
672 float m_floats[4];
673};
674
676{
677 double m_floats[4];
678
679};
680
682{
684 for (int i=0;i<4;i++)
685 dataOut.m_floats[i] = float(m_floats[i]);
686}
687
689{
690 for (int i=0;i<4;i++)
691 m_floats[i] = tf2Scalar(dataIn.m_floats[i]);
692}
693
694
696{
698 for (int i=0;i<4;i++)
699 dataOut.m_floats[i] = double(m_floats[i]);
700}
701
703{
704 for (int i=0;i<4;i++)
705 m_floats[i] = tf2Scalar(dataIn.m_floats[i]);
706}
707
708
710{
712 for (int i=0;i<4;i++)
713 dataOut.m_floats[i] = m_floats[i];
714}
715
717{
718 for (int i=0;i<4;i++)
719 m_floats[i] = dataIn.m_floats[i];
720}
721
722}
723
724#endif // TF2__LINEARMATH__VECTOR3_HPP_
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