Gazebo Math

API Reference

6.15.1
gz/math/Vector3.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef GZ_MATH_VECTOR3_HH_
18 #define GZ_MATH_VECTOR3_HH_
19 
20 #include <algorithm>
21 #include <cmath>
22 #include <fstream>
23 #include <iostream>
24 #include <limits>
25 
26 #include <gz/math/Helpers.hh>
27 #include <gz/math/config.hh>
28 
29 namespace ignition
30 {
31  namespace math
32  {
33  // Inline bracket to help doxygen filtering.
34  inline namespace IGNITION_MATH_VERSION_NAMESPACE {
35  //
40  template<typename T>
41  class Vector3
42  {
44  public: static const Vector3 Zero;
45 
47  public: static const Vector3 One;
48 
50  public: static const Vector3 UnitX;
51 
53  public: static const Vector3 UnitY;
54 
56  public: static const Vector3 UnitZ;
57 
59  public: static const Vector3 NaN;
60 
62  public: Vector3()
63  {
64  this->data[0] = 0;
65  this->data[1] = 0;
66  this->data[2] = 0;
67  }
68 
73  public: Vector3(const T &_x, const T &_y, const T &_z)
74  {
75  this->data[0] = _x;
76  this->data[1] = _y;
77  this->data[2] = _z;
78  }
79 
82  public: Vector3(const Vector3<T> &_v)
83  {
84  this->data[0] = _v[0];
85  this->data[1] = _v[1];
86  this->data[2] = _v[2];
87  }
88 
90  public: virtual ~Vector3() {}
91 
94  public: T Sum() const
95  {
96  return this->data[0] + this->data[1] + this->data[2];
97  }
98 
102  public: T Distance(const Vector3<T> &_pt) const
103  {
104  return static_cast<T>(sqrt(
105  (this->data[0]-_pt[0])*(this->data[0]-_pt[0]) +
106  (this->data[1]-_pt[1])*(this->data[1]-_pt[1]) +
107  (this->data[2]-_pt[2])*(this->data[2]-_pt[2])));
108  }
109 
115  public: T Distance(T _x, T _y, T _z) const
116  {
117  return this->Distance(Vector3(_x, _y, _z));
118  }
119 
122  public: T Length() const
123  {
124  return static_cast<T>(sqrt(this->SquaredLength()));
125  }
126 
129  public: T SquaredLength() const
130  {
131  return
132  this->data[0] * this->data[0] +
133  this->data[1] * this->data[1] +
134  this->data[2] * this->data[2];
135  }
136 
139  public: Vector3 Normalize()
140  {
141  T d = this->Length();
142 
143  if (!equal<T>(d, static_cast<T>(0.0)))
144  {
145  this->data[0] /= d;
146  this->data[1] /= d;
147  this->data[2] /= d;
148  }
149 
150  return *this;
151  }
152 
155  public: Vector3 Normalized() const
156  {
157  Vector3<T> result = *this;
158  result.Normalize();
159  return result;
160  }
161 
164  public: Vector3 Round()
165  {
166  this->data[0] = static_cast<T>(std::nearbyint(this->data[0]));
167  this->data[1] = static_cast<T>(std::nearbyint(this->data[1]));
168  this->data[2] = static_cast<T>(std::nearbyint(this->data[2]));
169  return *this;
170  }
171 
174  public: Vector3 Rounded() const
175  {
176  Vector3<T> result = *this;
177  result.Round();
178  return result;
179  }
180 
185  public: inline void Set(T _x = 0, T _y = 0, T _z = 0)
186  {
187  this->data[0] = _x;
188  this->data[1] = _y;
189  this->data[2] = _z;
190  }
191 
195  public: Vector3 Cross(const Vector3<T> &_v) const
196  {
197  return Vector3(this->data[1] * _v[2] - this->data[2] * _v[1],
198  this->data[2] * _v[0] - this->data[0] * _v[2],
199  this->data[0] * _v[1] - this->data[1] * _v[0]);
200  }
201 
205  public: T Dot(const Vector3<T> &_v) const
206  {
207  return this->data[0] * _v[0] +
208  this->data[1] * _v[1] +
209  this->data[2] * _v[2];
210  }
211 
220  public: T AbsDot(const Vector3<T> &_v) const
221  {
222  return std::abs(this->data[0] * _v[0]) +
223  std::abs(this->data[1] * _v[1]) +
224  std::abs(this->data[2] * _v[2]);
225  }
226 
229  public: Vector3 Abs() const
230  {
231  return Vector3(std::abs(this->data[0]),
232  std::abs(this->data[1]),
233  std::abs(this->data[2]));
234  }
235 
238  public: Vector3 Perpendicular() const
239  {
240  static const T sqrZero = static_cast<T>(1e-06 * 1e-06);
241 
242  Vector3<T> perp = this->Cross(Vector3(1, 0, 0));
243 
244  // Check the length of the vector
245  if (perp.SquaredLength() < sqrZero)
246  {
247  perp = this->Cross(Vector3(0, 1, 0));
248  }
249 
250  return perp;
251  }
252 
258  public: static Vector3 Normal(const Vector3<T> &_v1,
259  const Vector3<T> &_v2, const Vector3<T> &_v3)
260  {
261  Vector3<T> a = _v2 - _v1;
262  Vector3<T> b = _v3 - _v1;
263  Vector3<T> n = a.Cross(b);
264  return n.Normalize();
265  }
266 
271  public: T DistToLine(const Vector3<T> &_pt1, const Vector3 &_pt2)
272  {
273  T d = ((*this) - _pt1).Cross((*this) - _pt2).Length();
274  d = d / (_pt2 - _pt1).Length();
275  return d;
276  }
277 
281  public: void Max(const Vector3<T> &_v)
282  {
283  if (_v[0] > this->data[0])
284  this->data[0] = _v[0];
285  if (_v[1] > this->data[1])
286  this->data[1] = _v[1];
287  if (_v[2] > this->data[2])
288  this->data[2] = _v[2];
289  }
290 
294  public: void Min(const Vector3<T> &_v)
295  {
296  if (_v[0] < this->data[0])
297  this->data[0] = _v[0];
298  if (_v[1] < this->data[1])
299  this->data[1] = _v[1];
300  if (_v[2] < this->data[2])
301  this->data[2] = _v[2];
302  }
303 
306  public: T Max() const
307  {
308  return std::max(std::max(this->data[0], this->data[1]), this->data[2]);
309  }
310 
313  public: T Min() const
314  {
315  return std::min(std::min(this->data[0], this->data[1]), this->data[2]);
316  }
317 
321  public: Vector3 &operator=(const Vector3<T> &_v)
322  {
323  this->data[0] = _v[0];
324  this->data[1] = _v[1];
325  this->data[2] = _v[2];
326 
327  return *this;
328  }
329 
333  public: Vector3 &operator=(T _v)
334  {
335  this->data[0] = _v;
336  this->data[1] = _v;
337  this->data[2] = _v;
338 
339  return *this;
340  }
341 
345  public: Vector3 operator+(const Vector3<T> &_v) const
346  {
347  return Vector3(this->data[0] + _v[0],
348  this->data[1] + _v[1],
349  this->data[2] + _v[2]);
350  }
351 
355  public: const Vector3 &operator+=(const Vector3<T> &_v)
356  {
357  this->data[0] += _v[0];
358  this->data[1] += _v[1];
359  this->data[2] += _v[2];
360 
361  return *this;
362  }
363 
367  public: inline Vector3<T> operator+(const T _s) const
368  {
369  return Vector3<T>(this->data[0] + _s,
370  this->data[1] + _s,
371  this->data[2] + _s);
372  }
373 
378  public: friend inline Vector3<T> operator+(const T _s,
379  const Vector3<T> &_v)
380  {
381  return {_v.X() + _s, _v.Y() + _s, _v.Z() + _s};
382  }
383 
387  public: const Vector3<T> &operator+=(const T _s)
388  {
389  this->data[0] += _s;
390  this->data[1] += _s;
391  this->data[2] += _s;
392 
393  return *this;
394  }
395 
398  public: inline Vector3 operator-() const
399  {
400  return Vector3(-this->data[0], -this->data[1], -this->data[2]);
401  }
402 
406  public: inline Vector3<T> operator-(const Vector3<T> &_pt) const
407  {
408  return Vector3(this->data[0] - _pt[0],
409  this->data[1] - _pt[1],
410  this->data[2] - _pt[2]);
411  }
412 
416  public: const Vector3<T> &operator-=(const Vector3<T> &_pt)
417  {
418  this->data[0] -= _pt[0];
419  this->data[1] -= _pt[1];
420  this->data[2] -= _pt[2];
421 
422  return *this;
423  }
424 
428  public: inline Vector3<T> operator-(const T _s) const
429  {
430  return Vector3<T>(this->data[0] - _s,
431  this->data[1] - _s,
432  this->data[2] - _s);
433  }
434 
439  public: friend inline Vector3<T> operator-(const T _s,
440  const Vector3<T> &_v)
441  {
442  return {_s - _v.X(), _s - _v.Y(), _s - _v.Z()};
443  }
444 
448  public: const Vector3<T> &operator-=(const T _s)
449  {
450  this->data[0] -= _s;
451  this->data[1] -= _s;
452  this->data[2] -= _s;
453 
454  return *this;
455  }
456 
461  public: const Vector3<T> operator/(const Vector3<T> &_pt) const
462  {
463  return Vector3(this->data[0] / _pt[0],
464  this->data[1] / _pt[1],
465  this->data[2] / _pt[2]);
466  }
467 
472  public: const Vector3<T> &operator/=(const Vector3<T> &_pt)
473  {
474  this->data[0] /= _pt[0];
475  this->data[1] /= _pt[1];
476  this->data[2] /= _pt[2];
477 
478  return *this;
479  }
480 
485  public: const Vector3<T> operator/(T _v) const
486  {
487  return Vector3(this->data[0] / _v,
488  this->data[1] / _v,
489  this->data[2] / _v);
490  }
491 
496  public: const Vector3<T> &operator/=(T _v)
497  {
498  this->data[0] /= _v;
499  this->data[1] /= _v;
500  this->data[2] /= _v;
501 
502  return *this;
503  }
504 
509  public: Vector3<T> operator*(const Vector3<T> &_p) const
510  {
511  return Vector3(this->data[0] * _p[0],
512  this->data[1] * _p[1],
513  this->data[2] * _p[2]);
514  }
515 
520  public: const Vector3<T> &operator*=(const Vector3<T> &_v)
521  {
522  this->data[0] *= _v[0];
523  this->data[1] *= _v[1];
524  this->data[2] *= _v[2];
525 
526  return *this;
527  }
528 
532  public: inline Vector3<T> operator*(T _s) const
533  {
534  return Vector3<T>(this->data[0] * _s,
535  this->data[1] * _s,
536  this->data[2] * _s);
537  }
538 
543  public: friend inline Vector3<T> operator*(T _s, const Vector3<T> &_v)
544  {
545  return {_v.X() * _s, _v.Y() * _s, _v.Z() * _s};
546  }
547 
551  public: const Vector3<T> &operator*=(T _v)
552  {
553  this->data[0] *= _v;
554  this->data[1] *= _v;
555  this->data[2] *= _v;
556 
557  return *this;
558  }
559 
565  public: bool Equal(const Vector3 &_v, const T &_tol) const
566  {
567  return equal<T>(this->data[0], _v[0], _tol)
568  && equal<T>(this->data[1], _v[1], _tol)
569  && equal<T>(this->data[2], _v[2], _tol);
570  }
571 
576  public: bool operator==(const Vector3<T> &_v) const
577  {
578  return this->Equal(_v, static_cast<T>(1e-3));
579  }
580 
585  public: bool operator!=(const Vector3<T> &_v) const
586  {
587  return !(*this == _v);
588  }
589 
592  public: bool IsFinite() const
593  {
594  // std::isfinite works with floating point values,
595  // need to explicit cast to avoid ambiguity in vc++.
596  return std::isfinite(static_cast<double>(this->data[0])) &&
597  std::isfinite(static_cast<double>(this->data[1])) &&
598  std::isfinite(static_cast<double>(this->data[2]));
599  }
600 
602  public: inline void Correct()
603  {
604  // std::isfinite works with floating point values,
605  // need to explicit cast to avoid ambiguity in vc++.
606  if (!std::isfinite(static_cast<double>(this->data[0])))
607  this->data[0] = 0;
608  if (!std::isfinite(static_cast<double>(this->data[1])))
609  this->data[1] = 0;
610  if (!std::isfinite(static_cast<double>(this->data[2])))
611  this->data[2] = 0;
612  }
613 
618  public: T &operator[](const std::size_t _index)
619  {
620  return this->data[clamp(_index, IGN_ZERO_SIZE_T, IGN_TWO_SIZE_T)];
621  }
622 
627  public: T operator[](const std::size_t _index) const
628  {
629  return this->data[clamp(_index, IGN_ZERO_SIZE_T, IGN_TWO_SIZE_T)];
630  }
631 
634  public: void Round(int _precision)
635  {
636  this->data[0] = precision(this->data[0], _precision);
637  this->data[1] = precision(this->data[1], _precision);
638  this->data[2] = precision(this->data[2], _precision);
639  }
640 
645  public: bool Equal(const Vector3<T> &_v) const
646  {
647  return equal<T>(this->data[0], _v[0]) &&
648  equal<T>(this->data[1], _v[1]) &&
649  equal<T>(this->data[2], _v[2]);
650  }
651 
654  public: inline T X() const
655  {
656  return this->data[0];
657  }
658 
661  public: inline T Y() const
662  {
663  return this->data[1];
664  }
665 
668  public: inline T Z() const
669  {
670  return this->data[2];
671  }
672 
675  public: inline T &X()
676  {
677  return this->data[0];
678  }
679 
682  public: inline T &Y()
683  {
684  return this->data[1];
685  }
686 
689  public: inline T &Z()
690  {
691  return this->data[2];
692  }
693 
696  public: inline void X(const T &_v)
697  {
698  this->data[0] = _v;
699  }
700 
703  public: inline void Y(const T &_v)
704  {
705  this->data[1] = _v;
706  }
707 
710  public: inline void Z(const T &_v)
711  {
712  this->data[2] = _v;
713  }
714 
719  public: bool operator<(const Vector3<T> &_pt) const
720  {
721  return this->data[0] < _pt[0] || this->data[1] < _pt[1] ||
722  this->data[2] < _pt[2];
723  }
724 
729  public: friend std::ostream &operator<<(
730  std::ostream &_out, const gz::math::Vector3<T> &_pt)
731  {
732  _out << precision(_pt[0], 6) << " " << precision(_pt[1], 6) << " "
733  << precision(_pt[2], 6);
734  return _out;
735  }
736 
741  public: friend std::istream &operator>>(
742  std::istream &_in, gz::math::Vector3<T> &_pt)
743  {
744  // Skip white spaces
745  _in.setf(std::ios_base::skipws);
746  T x, y, z;
747  _in >> x >> y >> z;
748  if (!_in.fail())
749  {
750  _pt.Set(x, y, z);
751  }
752  return _in;
753  }
754 
756  private: T data[3];
757  };
758 
759  template<typename T> const Vector3<T> Vector3<T>::Zero(0, 0, 0);
760  template<typename T> const Vector3<T> Vector3<T>::One(1, 1, 1);
761  template<typename T> const Vector3<T> Vector3<T>::UnitX(1, 0, 0);
762  template<typename T> const Vector3<T> Vector3<T>::UnitY(0, 1, 0);
763  template<typename T> const Vector3<T> Vector3<T>::UnitZ(0, 0, 1);
764  template<typename T> const Vector3<T> Vector3<T>::NaN(
768 
772  }
773  }
774 }
775 #endif
static Vector3 Normal(const Vector3< T > &_v1, const Vector3< T > &_v2, const Vector3< T > &_v3)
Get a normal vector to a triangle.
Definition: gz/math/Vector3.hh:258
friend Vector3< T > operator-(const T _s, const Vector3< T > &_v)
Subtraction operators.
Definition: gz/math/Vector3.hh:439
const Vector3< T > & operator*=(T _v)
Multiplication operator.
Definition: gz/math/Vector3.hh:551
const Vector3< T > operator/(const Vector3< T > &_pt) const
Division operator.
Definition: gz/math/Vector3.hh:461
Definition: gz/math/AdditivelySeparableScalarField3.hh:27
Vector3(const Vector3< T > &_v)
Copy constructor.
Definition: gz/math/Vector3.hh:82
Vector3 Perpendicular() const
Return a vector that is perpendicular to this one.
Definition: gz/math/Vector3.hh:238
void Y(const T &_v)
Set the y value.
Definition: gz/math/Vector3.hh:703
T Length() const
Returns the length (magnitude) of the vector.
Definition: gz/math/Vector3.hh:122
bool operator==(const Vector3< T > &_v) const
Equal to operator.
Definition: gz/math/Vector3.hh:576
T AbsDot(const Vector3< T > &_v) const
Return the absolute dot product of this vector and another vector. This is similar to the Dot functio...
Definition: gz/math/Vector3.hh:220
T & X()
Get a mutable reference to the x value.
Definition: gz/math/Vector3.hh:675
T SquaredLength() const
Return the square of the length (magnitude) of the vector.
Definition: gz/math/Vector3.hh:129
bool Equal(const Vector3< T > &_v) const
Equality test.
Definition: gz/math/Vector3.hh:645
static const Vector3 One
math::Vector3(1, 1, 1)
Definition: gz/math/Vector3.hh:47
T & Y()
Get a mutable reference to the y value.
Definition: gz/math/Vector3.hh:682
T X() const
Get the x value.
Definition: gz/math/Vector3.hh:654
friend Vector3< T > operator+(const T _s, const Vector3< T > &_v)
Addition operators.
Definition: gz/math/Vector3.hh:378
T & Z()
Get a mutable reference to the z value.
Definition: gz/math/Vector3.hh:689
Vector3< T > operator+(const T _s) const
Addition operators.
Definition: gz/math/Vector3.hh:367
bool IsFinite() const
See if a point is finite (e.g., not nan)
Definition: gz/math/Vector3.hh:592
Vector3 & operator=(T _v)
Assignment operator.
Definition: gz/math/Vector3.hh:333
bool operator<(const Vector3< T > &_pt) const
Less than operator.
Definition: gz/math/Vector3.hh:719
Vector3< int > Vector3i
Definition: gz/math/Vector3.hh:769
void X(const T &_v)
Set the x value.
Definition: gz/math/Vector3.hh:696
const Vector3< T > & operator-=(const Vector3< T > &_pt)
Subtraction assignment operators.
Definition: gz/math/Vector3.hh:416
Vector3 Round()
Round to near whole number, return the result.
Definition: gz/math/Vector3.hh:164
void Min(const Vector3< T > &_v)
Set this vector's components to the minimum of itself and the passed in vector.
Definition: gz/math/Vector3.hh:294
const Vector3< T > & operator/=(const Vector3< T > &_pt)
Division assignment operator.
Definition: gz/math/Vector3.hh:472
static const Vector3 Zero
math::Vector3(0, 0, 0)
Definition: gz/math/Vector3.hh:44
T isfinite(T... args)
T precision(const T &_a, const unsigned int &_precision)
get value at a specified precision
Definition: gz/math/Helpers.hh:590
static const size_t IGN_TWO_SIZE_T
size_t type with a value of 2
Definition: gz/math/Helpers.hh:233
T Z() const
Get the z value.
Definition: gz/math/Vector3.hh:668
Vector3 & operator=(const Vector3< T > &_v)
Assignment operator.
Definition: gz/math/Vector3.hh:321
friend std::istream & operator>>(std::istream &_in, Vector3< T > &_pt)
Stream extraction operator.
Definition: gz/math/Vector3.hh:741
static const Vector3 UnitY
math::Vector3(0, 1, 0)
Definition: gz/math/Vector3.hh:53
STL class.
virtual ~Vector3()
Destructor.
Definition: gz/math/Vector3.hh:90
Vector3 Normalized() const
Return a normalized vector.
Definition: gz/math/Vector3.hh:155
Vector3 operator+(const Vector3< T > &_v) const
Addition operator.
Definition: gz/math/Vector3.hh:345
T Max() const
Get the maximum value in the vector.
Definition: gz/math/Vector3.hh:306
T clamp(T _v, T _min, T _max)
Simple clamping function.
Definition: gz/math/Helpers.hh:406
Vector3< T > operator-(const T _s) const
Subtraction operators.
Definition: gz/math/Vector3.hh:428
T setf(T... args)
The Vector3 class represents the generic vector containing 3 elements. Since it's commonly used to ke...
Definition: gz/math/Vector3.hh:41
Vector3< T > operator*(const Vector3< T > &_p) const
Multiplication operator.
Definition: gz/math/Vector3.hh:509
bool operator!=(const Vector3< T > &_v) const
Not equal to operator.
Definition: gz/math/Vector3.hh:585
T operator[](const std::size_t _index) const
Const-qualified array subscript operator.
Definition: gz/math/Vector3.hh:627
T Min() const
Get the minimum value in the vector.
Definition: gz/math/Vector3.hh:313
Vector3< T > operator-(const Vector3< T > &_pt) const
Subtraction operators.
Definition: gz/math/Vector3.hh:406
const Vector3< T > & operator*=(const Vector3< T > &_v)
Multiplication assignment operators.
Definition: gz/math/Vector3.hh:520
void Set(T _x=0, T _y=0, T _z=0)
Set the contents of the vector.
Definition: gz/math/Vector3.hh:185
friend std::ostream & operator<<(std::ostream &_out, const Vector3< T > &_pt)
Stream insertion operator.
Definition: gz/math/Vector3.hh:729
T min(T... args)
T Distance(T _x, T _y, T _z) const
Calc distance to the given point.
Definition: gz/math/Vector3.hh:115
bool Equal(const Vector3 &_v, const T &_tol) const
Equality test with tolerance.
Definition: gz/math/Vector3.hh:565
void Round(int _precision)
Round all values to _precision decimal places.
Definition: gz/math/Vector3.hh:634
Vector3()
Constructor.
Definition: gz/math/Vector3.hh:62
const Vector3< T > & operator+=(const T _s)
Addition assignment operator.
Definition: gz/math/Vector3.hh:387
Vector3 operator-() const
Negation operator.
Definition: gz/math/Vector3.hh:398
friend Vector3< T > operator*(T _s, const Vector3< T > &_v)
Multiplication operators.
Definition: gz/math/Vector3.hh:543
T fail(T... args)
Vector3 Normalize()
Normalize the vector length.
Definition: gz/math/Vector3.hh:139
Vector3< T > operator*(T _s) const
Multiplication operators.
Definition: gz/math/Vector3.hh:532
static const Vector3 UnitX
math::Vector3(1, 0, 0)
Definition: gz/math/Vector3.hh:50
void Max(const Vector3< T > &_v)
Set this vector's components to the maximum of itself and the passed in vector.
Definition: gz/math/Vector3.hh:281
const Vector3< T > & operator-=(const T _s)
Subtraction assignment operator.
Definition: gz/math/Vector3.hh:448
static const Vector3 NaN
math::Vector3(NaN, NaN, NaN)
Definition: gz/math/Vector3.hh:59
T Sum() const
Return the sum of the values.
Definition: gz/math/Vector3.hh:94
static const Vector3 UnitZ
math::Vector3(0, 0, 1)
Definition: gz/math/Vector3.hh:56
static const size_t IGN_ZERO_SIZE_T
size_t type with a value of 0
Definition: gz/math/Helpers.hh:227
const Vector3< T > & operator/=(T _v)
Division assignment operator.
Definition: gz/math/Vector3.hh:496
T nearbyint(T... args)
const Vector3 & operator+=(const Vector3< T > &_v)
Addition assignment operator.
Definition: gz/math/Vector3.hh:355
T Dot(const Vector3< T > &_v) const
Return the dot product of this vector and another vector.
Definition: gz/math/Vector3.hh:205
T DistToLine(const Vector3< T > &_pt1, const Vector3 &_pt2)
Get distance to an infinite line defined by 2 points.
Definition: gz/math/Vector3.hh:271
void Correct()
Corrects any nan values.
Definition: gz/math/Vector3.hh:602
const Vector3< T > operator/(T _v) const
Division operator.
Definition: gz/math/Vector3.hh:485
Vector3< float > Vector3f
Definition: gz/math/Vector3.hh:771
T & operator[](const std::size_t _index)
Array subscript operator.
Definition: gz/math/Vector3.hh:618
void Z(const T &_v)
Set the z value.
Definition: gz/math/Vector3.hh:710
T max(T... args)
T Distance(const Vector3< T > &_pt) const
Calc distance to the given point.
Definition: gz/math/Vector3.hh:102
Vector3 Abs() const
Get the absolute value of the vector.
Definition: gz/math/Vector3.hh:229
STL class.
T Y() const
Get the y value.
Definition: gz/math/Vector3.hh:661
Vector3< double > Vector3d
Definition: gz/math/Vector3.hh:770
Vector3(const T &_x, const T &_y, const T &_z)
Constructor.
Definition: gz/math/Vector3.hh:73
Vector3 Cross(const Vector3< T > &_v) const
Return the cross product of this vector with another vector.
Definition: gz/math/Vector3.hh:195
Vector3 Rounded() const
Get a rounded version of this vector.
Definition: gz/math/Vector3.hh:174