melodic/include/tf2/LinearMath/Vector3.h
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 /*
3 Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/
4 
5 This software is provided 'as-is', without any express or implied warranty.
6 In no event will the authors be held liable for any damages arising from the use of this software.
7 Permission is granted to anyone to use this software for any purpose,
8 including commercial applications, and to alter it and redistribute it freely,
9 subject to the following restrictions:
10 
11 1. 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.
12 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
13 3. This notice may not be removed or altered from any source distribution.
14 */
15 
16 
17 
18 #ifndef TF2_VECTOR3_H
19 #define TF2_VECTOR3_H
20 
21 
22 #include "Scalar.h"
23 #include "MinMax.h"
24 
25 namespace tf2
26 {
27 
28 #define Vector3Data Vector3DoubleData
29 #define Vector3DataName "Vector3DoubleData"
30 
31 
32 
33 
39 {
40 public:
41 
42 #if defined (__SPU__) && defined (__CELLOS_LV2__)
43  tf2Scalar m_floats[4];
44 public:
45  TF2SIMD_FORCE_INLINE const vec_float4& get128() const
46  {
47  return *((const vec_float4*)&m_floats[0]);
48  }
49 public:
50 #else //__CELLOS_LV2__ __SPU__
51 #ifdef TF2_USE_SSE // _WIN32
52  union {
53  __m128 mVec128;
54  tf2Scalar m_floats[4];
55  };
56  TF2SIMD_FORCE_INLINE __m128 get128() const
57  {
58  return mVec128;
59  }
60  TF2SIMD_FORCE_INLINE void set128(__m128 v128)
61  {
62  mVec128 = v128;
63  }
64 #else
65  tf2Scalar m_floats[4];
66 #endif
67 #endif //__CELLOS_LV2__ __SPU__
68 
69  public:
70 
73 
74 
75 
81  TF2SIMD_FORCE_INLINE Vector3(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z)
82  {
83  m_floats[0] = x;
84  m_floats[1] = y;
85  m_floats[2] = z;
86  m_floats[3] = tf2Scalar(0.);
87  }
88 
91  TF2SIMD_FORCE_INLINE Vector3& operator+=(const Vector3& v)
92  {
93 
94  m_floats[0] += v.m_floats[0]; m_floats[1] += v.m_floats[1];m_floats[2] += v.m_floats[2];
95  return *this;
96  }
97 
98 
101  TF2SIMD_FORCE_INLINE Vector3& operator-=(const Vector3& v)
102  {
103  m_floats[0] -= v.m_floats[0]; m_floats[1] -= v.m_floats[1];m_floats[2] -= v.m_floats[2];
104  return *this;
105  }
108  TF2SIMD_FORCE_INLINE Vector3& operator*=(const tf2Scalar& s)
109  {
110  m_floats[0] *= s; m_floats[1] *= s;m_floats[2] *= s;
111  return *this;
112  }
113 
116  TF2SIMD_FORCE_INLINE Vector3& operator/=(const tf2Scalar& s)
117  {
118  tf2FullAssert(s != tf2Scalar(0.0));
119  return *this *= tf2Scalar(1.0) / s;
120  }
121 
124  TF2SIMD_FORCE_INLINE tf2Scalar dot(const Vector3& v) const
125  {
126  return m_floats[0] * v.m_floats[0] + m_floats[1] * v.m_floats[1] +m_floats[2] * v.m_floats[2];
127  }
128 
130  TF2SIMD_FORCE_INLINE tf2Scalar length2() const
131  {
132  return dot(*this);
133  }
134 
137  {
138  return tf2Sqrt(length2());
139  }
140 
143  TF2SIMD_FORCE_INLINE tf2Scalar distance2(const Vector3& v) const;
144 
147  TF2SIMD_FORCE_INLINE tf2Scalar distance(const Vector3& v) const;
148 
152  {
153  return *this /= length();
154  }
155 
157  TF2SIMD_FORCE_INLINE Vector3 normalized() const;
158 
162  TF2SIMD_FORCE_INLINE Vector3 rotate( const Vector3& wAxis, const tf2Scalar angle ) const;
163 
167  {
168  tf2Scalar s = tf2Sqrt(length2() * v.length2());
169  tf2FullAssert(s != tf2Scalar(0.0));
170  return tf2Acos(dot(v) / s);
171  }
173  TF2SIMD_FORCE_INLINE Vector3 absolute() const
174  {
175  return Vector3(
176  tf2Fabs(m_floats[0]),
177  tf2Fabs(m_floats[1]),
178  tf2Fabs(m_floats[2]));
179  }
182  TF2SIMD_FORCE_INLINE Vector3 cross(const Vector3& v) const
183  {
184  return Vector3(
185  m_floats[1] * v.m_floats[2] -m_floats[2] * v.m_floats[1],
186  m_floats[2] * v.m_floats[0] - m_floats[0] * v.m_floats[2],
187  m_floats[0] * v.m_floats[1] - m_floats[1] * v.m_floats[0]);
188  }
189 
190  TF2SIMD_FORCE_INLINE tf2Scalar triple(const Vector3& v1, const Vector3& v2) const
191  {
192  return m_floats[0] * (v1.m_floats[1] * v2.m_floats[2] - v1.m_floats[2] * v2.m_floats[1]) +
193  m_floats[1] * (v1.m_floats[2] * v2.m_floats[0] - v1.m_floats[0] * v2.m_floats[2]) +
194  m_floats[2] * (v1.m_floats[0] * v2.m_floats[1] - v1.m_floats[1] * v2.m_floats[0]);
195  }
196 
199  TF2SIMD_FORCE_INLINE int minAxis() const
200  {
201  return m_floats[0] < m_floats[1] ? (m_floats[0] <m_floats[2] ? 0 : 2) : (m_floats[1] <m_floats[2] ? 1 : 2);
202  }
203 
206  TF2SIMD_FORCE_INLINE int maxAxis() const
207  {
208  return m_floats[0] < m_floats[1] ? (m_floats[1] <m_floats[2] ? 2 : 1) : (m_floats[0] <m_floats[2] ? 2 : 0);
209  }
210 
211  TF2SIMD_FORCE_INLINE int furthestAxis() const
212  {
213  return absolute().minAxis();
214  }
215 
216  TF2SIMD_FORCE_INLINE int closestAxis() const
217  {
218  return absolute().maxAxis();
219  }
220 
221  TF2SIMD_FORCE_INLINE void setInterpolate3(const Vector3& v0, const Vector3& v1, tf2Scalar rt)
222  {
223  tf2Scalar s = tf2Scalar(1.0) - rt;
224  m_floats[0] = s * v0.m_floats[0] + rt * v1.m_floats[0];
225  m_floats[1] = s * v0.m_floats[1] + rt * v1.m_floats[1];
226  m_floats[2] = s * v0.m_floats[2] + rt * v1.m_floats[2];
227  //don't do the unused w component
228  // m_co[3] = s * v0[3] + rt * v1[3];
229  }
230 
234  TF2SIMD_FORCE_INLINE Vector3 lerp(const Vector3& v, const tf2Scalar& t) const
235  {
236  return Vector3(m_floats[0] + (v.m_floats[0] - m_floats[0]) * t,
237  m_floats[1] + (v.m_floats[1] - m_floats[1]) * t,
238  m_floats[2] + (v.m_floats[2] -m_floats[2]) * t);
239  }
240 
243  TF2SIMD_FORCE_INLINE Vector3& operator*=(const Vector3& v)
244  {
245  m_floats[0] *= v.m_floats[0]; m_floats[1] *= v.m_floats[1];m_floats[2] *= v.m_floats[2];
246  return *this;
247  }
248 
250  TF2SIMD_FORCE_INLINE const tf2Scalar& getX() const { return m_floats[0]; }
252  TF2SIMD_FORCE_INLINE const tf2Scalar& getY() const { return m_floats[1]; }
254  TF2SIMD_FORCE_INLINE const tf2Scalar& getZ() const { return m_floats[2]; }
256  TF2SIMD_FORCE_INLINE void setX(tf2Scalar x) { m_floats[0] = x;};
258  TF2SIMD_FORCE_INLINE void setY(tf2Scalar y) { m_floats[1] = y;};
260  TF2SIMD_FORCE_INLINE void setZ(tf2Scalar z) {m_floats[2] = z;};
262  TF2SIMD_FORCE_INLINE void setW(tf2Scalar w) { m_floats[3] = w;};
264  TF2SIMD_FORCE_INLINE const tf2Scalar& x() const { return m_floats[0]; }
266  TF2SIMD_FORCE_INLINE const tf2Scalar& y() const { return m_floats[1]; }
268  TF2SIMD_FORCE_INLINE const tf2Scalar& z() const { return m_floats[2]; }
270  TF2SIMD_FORCE_INLINE const tf2Scalar& w() const { return m_floats[3]; }
271 
272  //TF2SIMD_FORCE_INLINE tf2Scalar& operator[](int i) { return (&m_floats[0])[i]; }
273  //TF2SIMD_FORCE_INLINE const tf2Scalar& operator[](int i) const { return (&m_floats[0])[i]; }
275  TF2SIMD_FORCE_INLINE operator tf2Scalar *() { return &m_floats[0]; }
276  TF2SIMD_FORCE_INLINE operator const tf2Scalar *() const { return &m_floats[0]; }
277 
278  TF2SIMD_FORCE_INLINE bool operator==(const Vector3& other) const
279  {
280  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]));
281  }
282 
283  TF2SIMD_FORCE_INLINE bool operator!=(const Vector3& other) const
284  {
285  return !(*this == other);
286  }
287 
291  TF2SIMD_FORCE_INLINE void setMax(const Vector3& other)
292  {
293  tf2SetMax(m_floats[0], other.m_floats[0]);
294  tf2SetMax(m_floats[1], other.m_floats[1]);
295  tf2SetMax(m_floats[2], other.m_floats[2]);
296  tf2SetMax(m_floats[3], other.w());
297  }
301  TF2SIMD_FORCE_INLINE void setMin(const Vector3& other)
302  {
303  tf2SetMin(m_floats[0], other.m_floats[0]);
304  tf2SetMin(m_floats[1], other.m_floats[1]);
305  tf2SetMin(m_floats[2], other.m_floats[2]);
306  tf2SetMin(m_floats[3], other.w());
307  }
308 
309  TF2SIMD_FORCE_INLINE void setValue(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z)
310  {
311  m_floats[0]=x;
312  m_floats[1]=y;
313  m_floats[2]=z;
314  m_floats[3] = tf2Scalar(0.);
315  }
316 
317  void getSkewSymmetricMatrix(Vector3* v0,Vector3* v1,Vector3* v2) const
318  {
319  v0->setValue(0. ,-z() ,y());
320  v1->setValue(z() ,0. ,-x());
321  v2->setValue(-y() ,x() ,0.);
322  }
323 
324  void setZero()
325  {
326  setValue(tf2Scalar(0.),tf2Scalar(0.),tf2Scalar(0.));
327  }
328 
329  TF2SIMD_FORCE_INLINE bool isZero() const
330  {
331  return m_floats[0] == tf2Scalar(0) && m_floats[1] == tf2Scalar(0) && m_floats[2] == tf2Scalar(0);
332  }
333 
334  TF2SIMD_FORCE_INLINE bool fuzzyZero() const
335  {
336  return length2() < TF2SIMD_EPSILON;
337  }
338 
339  TF2SIMD_FORCE_INLINE void serialize(struct Vector3Data& dataOut) const;
340 
341  TF2SIMD_FORCE_INLINE void deSerialize(const struct Vector3Data& dataIn);
342 
343  TF2SIMD_FORCE_INLINE void serializeFloat(struct Vector3FloatData& dataOut) const;
344 
345  TF2SIMD_FORCE_INLINE void deSerializeFloat(const struct Vector3FloatData& dataIn);
346 
347  TF2SIMD_FORCE_INLINE void serializeDouble(struct Vector3DoubleData& dataOut) const;
348 
349  TF2SIMD_FORCE_INLINE void deSerializeDouble(const struct Vector3DoubleData& dataIn);
350 
351 };
352 
355 operator+(const Vector3& v1, const Vector3& v2)
356 {
357  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]);
358 }
359 
362 operator*(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 
369 operator-(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 }
375 operator-(const Vector3& v)
376 {
377  return Vector3(-v.m_floats[0], -v.m_floats[1], -v.m_floats[2]);
378 }
379 
382 operator*(const Vector3& v, const tf2Scalar& s)
383 {
384  return Vector3(v.m_floats[0] * s, v.m_floats[1] * s, v.m_floats[2] * s);
385 }
386 
389 operator*(const tf2Scalar& s, const Vector3& v)
390 {
391  return v * s;
392 }
393 
396 operator/(const Vector3& v, const tf2Scalar& s)
397 {
398  tf2FullAssert(s != tf2Scalar(0.0));
399  return v * (tf2Scalar(1.0) / s);
400 }
401 
404 operator/(const Vector3& v1, const Vector3& v2)
405 {
406  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]);
407 }
408 
411 tf2Dot(const Vector3& v1, const Vector3& v2)
412 {
413  return v1.dot(v2);
414 }
415 
416 
419 tf2Distance2(const Vector3& v1, const Vector3& v2)
420 {
421  return v1.distance2(v2);
422 }
423 
424 
427 tf2Distance(const Vector3& v1, const Vector3& v2)
428 {
429  return v1.distance(v2);
430 }
431 
434 tf2Angle(const Vector3& v1, const Vector3& v2)
435 {
436  return v1.angle(v2);
437 }
438 
441 tf2Cross(const Vector3& v1, const Vector3& v2)
442 {
443  return v1.cross(v2);
444 }
445 
447 tf2Triple(const Vector3& v1, const Vector3& v2, const Vector3& v3)
448 {
449  return v1.triple(v2, v3);
450 }
451 
457 lerp(const Vector3& v1, const Vector3& v2, const tf2Scalar& t)
458 {
459  return v1.lerp(v2, t);
460 }
461 
462 
463 
464 TF2SIMD_FORCE_INLINE tf2Scalar Vector3::distance2(const Vector3& v) const
465 {
466  return (v - *this).length2();
467 }
468 
469 TF2SIMD_FORCE_INLINE tf2Scalar Vector3::distance(const Vector3& v) const
470 {
471  return (v - *this).length();
472 }
473 
474 TF2SIMD_FORCE_INLINE Vector3 Vector3::normalized() const
475 {
476  return *this / length();
477 }
478 
479 TF2SIMD_FORCE_INLINE Vector3 Vector3::rotate( const Vector3& wAxis, const tf2Scalar angle ) const
480 {
481  // wAxis must be a unit lenght vector
482 
483  Vector3 o = wAxis * wAxis.dot( *this );
484  Vector3 x = *this - o;
485  Vector3 y;
486 
487  y = wAxis.cross( *this );
488 
489  return ( o + x * tf2Cos( angle ) + y * tf2Sin( angle ) );
490 }
491 
492 class tf2Vector4 : public Vector3
493 {
494 public:
495 
497 
498 
499  TF2SIMD_FORCE_INLINE tf2Vector4(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z,const tf2Scalar& w)
500  : Vector3(x,y,z)
501  {
502  m_floats[3] = w;
503  }
504 
505 
507  {
508  return tf2Vector4(
509  tf2Fabs(m_floats[0]),
510  tf2Fabs(m_floats[1]),
511  tf2Fabs(m_floats[2]),
512  tf2Fabs(m_floats[3]));
513  }
514 
515 
516 
517  tf2Scalar getW() const { return m_floats[3];}
518 
519 
520  TF2SIMD_FORCE_INLINE int maxAxis4() const
521  {
522  int maxIndex = -1;
524  if (m_floats[0] > maxVal)
525  {
526  maxIndex = 0;
527  maxVal = m_floats[0];
528  }
529  if (m_floats[1] > maxVal)
530  {
531  maxIndex = 1;
532  maxVal = m_floats[1];
533  }
534  if (m_floats[2] > maxVal)
535  {
536  maxIndex = 2;
537  maxVal =m_floats[2];
538  }
539  if (m_floats[3] > maxVal)
540  {
541  maxIndex = 3;
542  }
543 
544 
545 
546 
547  return maxIndex;
548 
549  }
550 
551 
552  TF2SIMD_FORCE_INLINE int minAxis4() const
553  {
554  int minIndex = -1;
556  if (m_floats[0] < minVal)
557  {
558  minIndex = 0;
559  minVal = m_floats[0];
560  }
561  if (m_floats[1] < minVal)
562  {
563  minIndex = 1;
564  minVal = m_floats[1];
565  }
566  if (m_floats[2] < minVal)
567  {
568  minIndex = 2;
569  minVal =m_floats[2];
570  }
571  if (m_floats[3] < minVal)
572  {
573  minIndex = 3;
574  }
575 
576  return minIndex;
577 
578  }
579 
580 
582  {
583  return absolute4().maxAxis4();
584  }
585 
586 
587 
588 
596 /* void getValue(tf2Scalar *m) const
597  {
598  m[0] = m_floats[0];
599  m[1] = m_floats[1];
600  m[2] =m_floats[2];
601  }
602 */
609  TF2SIMD_FORCE_INLINE void setValue(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z,const tf2Scalar& w)
610  {
611  m_floats[0]=x;
612  m_floats[1]=y;
613  m_floats[2]=z;
614  m_floats[3]=w;
615  }
616 
617 
618 };
619 
620 
622 TF2SIMD_FORCE_INLINE void tf2SwapScalarEndian(const tf2Scalar& sourceVal, tf2Scalar& destVal)
623 {
624  unsigned char* dest = (unsigned char*) &destVal;
625  const unsigned char* src = (const unsigned char*) &sourceVal;
626  dest[0] = src[7];
627  dest[1] = src[6];
628  dest[2] = src[5];
629  dest[3] = src[4];
630  dest[4] = src[3];
631  dest[5] = src[2];
632  dest[6] = src[1];
633  dest[7] = src[0];
634 }
636 TF2SIMD_FORCE_INLINE void tf2SwapVector3Endian(const Vector3& sourceVec, Vector3& destVec)
637 {
638  for (int i=0;i<4;i++)
639  {
640  tf2SwapScalarEndian(sourceVec[i],destVec[i]);
641  }
642 
643 }
644 
647 {
648 
649  Vector3 swappedVec;
650  for (int i=0;i<4;i++)
651  {
652  tf2SwapScalarEndian(vector[i],swappedVec[i]);
653  }
654  vector = swappedVec;
655 }
656 
658 {
659  if (tf2Fabs(n.z()) > TF2SIMDSQRT12) {
660  // choose p in y-z plane
661  tf2Scalar a = n[1]*n[1] + n[2]*n[2];
662  tf2Scalar k = tf2RecipSqrt (a);
663  p.setValue(0,-n[2]*k,n[1]*k);
664  // set q = n x p
665  q.setValue(a*k,-n[0]*p[2],n[0]*p[1]);
666  }
667  else {
668  // choose p in x-y plane
669  tf2Scalar a = n.x()*n.x() + n.y()*n.y();
670  tf2Scalar k = tf2RecipSqrt (a);
671  p.setValue(-n.y()*k,n.x()*k,0);
672  // set q = n x p
673  q.setValue(-n.z()*p.y(),n.z()*p.x(),a*k);
674  }
675 }
676 
677 
678 struct Vector3FloatData
679 {
680  float m_floats[4];
681 };
682 
683 struct Vector3DoubleData
684 {
685  double m_floats[4];
686 
687 };
688 
689 TF2SIMD_FORCE_INLINE void Vector3::serializeFloat(struct Vector3FloatData& dataOut) const
690 {
692  for (int i=0;i<4;i++)
693  dataOut.m_floats[i] = float(m_floats[i]);
694 }
695 
696 TF2SIMD_FORCE_INLINE void Vector3::deSerializeFloat(const struct Vector3FloatData& dataIn)
697 {
698  for (int i=0;i<4;i++)
699  m_floats[i] = tf2Scalar(dataIn.m_floats[i]);
700 }
701 
702 
703 TF2SIMD_FORCE_INLINE void Vector3::serializeDouble(struct Vector3DoubleData& dataOut) const
704 {
706  for (int i=0;i<4;i++)
707  dataOut.m_floats[i] = double(m_floats[i]);
708 }
709 
710 TF2SIMD_FORCE_INLINE void Vector3::deSerializeDouble(const struct Vector3DoubleData& dataIn)
711 {
712  for (int i=0;i<4;i++)
713  m_floats[i] = tf2Scalar(dataIn.m_floats[i]);
714 }
715 
716 
717 TF2SIMD_FORCE_INLINE void Vector3::serialize(struct Vector3Data& dataOut) const
718 {
720  for (int i=0;i<4;i++)
721  dataOut.m_floats[i] = m_floats[i];
722 }
723 
724 TF2SIMD_FORCE_INLINE void Vector3::deSerialize(const struct Vector3Data& dataIn)
725 {
726  for (int i=0;i<4;i++)
727  m_floats[i] = dataIn.m_floats[i];
728 }
729 
730 }
731 
732 #endif //TF2_VECTOR3_H
tf2::tf2SwapScalarEndian
TF2SIMD_FORCE_INLINE void tf2SwapScalarEndian(const tf2Scalar &sourceVal, tf2Scalar &destVal)
tf2SwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization
Definition: melodic/include/tf2/LinearMath/Vector3.h:622
tf2::dot
TF2SIMD_FORCE_INLINE tf2Scalar dot(const Quaternion &q1, const Quaternion &q2)
Calculate the dot product between two quaternions.
Definition: melodic/include/tf2/LinearMath/Quaternion.h:391
Scalar.h
tf2::Vector3FloatData::m_floats
float m_floats[4]
Definition: melodic/include/tf2/LinearMath/Vector3.h:680
geometry_msgs::Vector3
::geometry_msgs::Vector3_< std::allocator< void > > Vector3
Definition: kinetic/include/geometry_msgs/Vector3.h:58
tf2::tf2Vector4::closestAxis4
TF2SIMD_FORCE_INLINE int closestAxis4() const
tf2::operator/
TF2SIMD_FORCE_INLINE Vector3 operator/(const Vector3 &v, const tf2Scalar &s)
Return the vector inversely scaled by s.
Definition: melodic/include/tf2/LinearMath/Vector3.h:396
tf2::tf2UnSwapVector3Endian
TF2SIMD_FORCE_INLINE void tf2UnSwapVector3Endian(Vector3 &vector)
tf2UnSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization
Definition: melodic/include/tf2/LinearMath/Vector3.h:646
s
XmlRpcServer s
roswrap::serialization::serialize
void serialize(Stream &stream, const T &t)
Serialize an object. Stream here should normally be a ros::serialization::OStream.
Definition: serialization.h:153
TF2SIMD_EPSILON
#define TF2SIMD_EPSILON
Definition: Scalar.h:203
tf2::tf2Vector4::maxAxis4
TF2SIMD_FORCE_INLINE int maxAxis4() const
tf2Sin
TF2SIMD_FORCE_INLINE tf2Scalar tf2Sin(tf2Scalar x)
Definition: Scalar.h:181
tf2::tf2Dot
TF2SIMD_FORCE_INLINE tf2Scalar tf2Dot(const Vector3 &v1, const Vector3 &v2)
Return the dot product between two vectors.
Definition: melodic/include/tf2/LinearMath/Vector3.h:411
tf2::tf2Vector4::minAxis4
TF2SIMD_FORCE_INLINE int minAxis4() const
tf2::lerp
TF2SIMD_FORCE_INLINE Vector3 lerp(const Vector3 &v1, const Vector3 &v2, const tf2Scalar &t)
Return the linear interpolation between two vectors.
Definition: melodic/include/tf2/LinearMath/Vector3.h:457
tf2::tf2Vector4::setValue
TF2SIMD_FORCE_INLINE void setValue(const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z, const tf2Scalar &w)
tf2::tf2Vector4::tf2Vector4
TF2SIMD_FORCE_INLINE tf2Vector4()
tf2Sqrt
TF2SIMD_FORCE_INLINE tf2Scalar tf2Sqrt(tf2Scalar x)
Definition: Scalar.h:178
MinMax.h
normalize
void normalize(float &angle)
Definition: radar_object_marker.cpp:79
tf2::ATTRIBUTE_ALIGNED16
ATTRIBUTE_ALIGNED16(class) QuadWord
The QuadWord class is base class for Vector3 and Quaternion. Some issues under PS3 Linux with IBM 2....
Definition: QuadWord.h:34
tf2FullAssert
#define tf2FullAssert(x)
Definition: Scalar.h:149
tf2::tf2Distance2
TF2SIMD_FORCE_INLINE tf2Scalar tf2Distance2(const Vector3 &v1, const Vector3 &v2)
Return the distance squared between two vectors.
Definition: melodic/include/tf2/LinearMath/Vector3.h:419
TF2_LARGE_FLOAT
#define TF2_LARGE_FLOAT
Definition: Scalar.h:162
tf2::tf2Angle
TF2SIMD_FORCE_INLINE tf2Scalar tf2Angle(const Vector3 &v1, const Vector3 &v2)
Return the angle between two vectors.
Definition: melodic/include/tf2/LinearMath/Vector3.h:434
tf2::tf2Vector4::getW
tf2Scalar getW() const
tf2Acos
TF2SIMD_FORCE_INLINE tf2Scalar tf2Acos(tf2Scalar x)
Definition: Scalar.h:183
tf2::tf2Cross
TF2SIMD_FORCE_INLINE Vector3 tf2Cross(const Vector3 &v1, const Vector3 &v2)
Return the cross product of two vectors.
Definition: melodic/include/tf2/LinearMath/Vector3.h:441
tf2::operator==
TF2SIMD_FORCE_INLINE bool operator==(const Matrix3x3 &m1, const Matrix3x3 &m2)
Equality operator between two matrices It will test all elements are equal.
Definition: Matrix3x3.h:640
tf2::operator*
TF2SIMD_FORCE_INLINE Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)
Definition: Matrix3x3.h:602
tf2::tf2SwapVector3Endian
TF2SIMD_FORCE_INLINE void tf2SwapVector3Endian(const Vector3 &sourceVec, Vector3 &destVec)
tf2SwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization
Definition: melodic/include/tf2/LinearMath/Vector3.h:636
Vector3
tf2RecipSqrt
#define tf2RecipSqrt(x)
Definition: Scalar.h:200
TF2SIMD_FORCE_INLINE
#define TF2SIMD_FORCE_INLINE
Definition: Scalar.h:130
tf2::tf2PlaneSpace1
TF2SIMD_FORCE_INLINE void tf2PlaneSpace1(const Vector3 &n, Vector3 &p, Vector3 &q)
Definition: melodic/include/tf2/LinearMath/Vector3.h:657
tf2SetMin
TF2SIMD_FORCE_INLINE void tf2SetMin(T &a, const T &b)
Definition: MinMax.h:40
tf2Cos
TF2SIMD_FORCE_INLINE tf2Scalar tf2Cos(tf2Scalar x)
Definition: Scalar.h:180
tf2::tf2Triple
TF2SIMD_FORCE_INLINE tf2Scalar tf2Triple(const Vector3 &v1, const Vector3 &v2, const Vector3 &v3)
Definition: melodic/include/tf2/LinearMath/Vector3.h:447
tf2
tf2Fabs
TF2SIMD_FORCE_INLINE tf2Scalar tf2Fabs(tf2Scalar x)
Definition: Scalar.h:179
sick_scan_base.h
tf2::angle
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
Return the half angle between two quaternions.
Definition: melodic/include/tf2/LinearMath/Quaternion.h:406
tf2::operator+
TF2SIMD_FORCE_INLINE Vector3 operator+(const Vector3 &v1, const Vector3 &v2)
Return the sum of two vectors (Point symantics)
Definition: melodic/include/tf2/LinearMath/Vector3.h:355
tf2::length
TF2SIMD_FORCE_INLINE tf2Scalar length(const Quaternion &q)
Return the length of a quaternion.
Definition: melodic/include/tf2/LinearMath/Quaternion.h:399
tf2Scalar
double tf2Scalar
tf2::tf2Distance
TF2SIMD_FORCE_INLINE tf2Scalar tf2Distance(const Vector3 &v1, const Vector3 &v2)
Return the distance between two vectors.
Definition: melodic/include/tf2/LinearMath/Vector3.h:427
tf2::operator-
TF2SIMD_FORCE_INLINE Quaternion operator-(const Quaternion &q)
Return the negative of a quaternion.
Definition: melodic/include/tf2/LinearMath/Quaternion.h:355
operator!=
bool operator!=(const TiXmlString &a, const TiXmlString &b)
Definition: tinystr.h:293
TF2SIMDSQRT12
#define TF2SIMDSQRT12
Definition: Scalar.h:198
tf2SetMax
TF2SIMD_FORCE_INLINE void tf2SetMax(T &a, const T &b)
Definition: MinMax.h:49
tf2::tf2Vector4::absolute4
TF2SIMD_FORCE_INLINE tf2Vector4 absolute4() const
t
geometry_msgs::TransformStamped t
Vector3Data
#define Vector3Data
Definition: melodic/include/tf2/LinearMath/Vector3.h:28
tf2::Vector3DoubleData::m_floats
double m_floats[4]
Definition: melodic/include/tf2/LinearMath/Vector3.h:685


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:13