Browse Source

AP_Math: added xy() method on Vector3

useful for getting xy length
zr-v5.1
Andrew Tridgell 4 years ago
parent
commit
f19b604a0c
  1. 7
      libraries/AP_Math/vector3.cpp
  2. 6
      libraries/AP_Math/vector3.h

7
libraries/AP_Math/vector3.cpp

@ -617,6 +617,13 @@ bool Vector3<T>::segment_plane_intersect(const Vector3<T>& seg_start, const Vect @@ -617,6 +617,13 @@ bool Vector3<T>::segment_plane_intersect(const Vector3<T>& seg_start, const Vect
return true;
}
// return xy components of a vector3
template <typename T>
Vector2<T> Vector3<T>::xy()
{
return Vector2<T>{x,y};
}
// define for float and double
template class Vector3<float>;
template class Vector3<double>;

6
libraries/AP_Math/vector3.h

@ -63,6 +63,9 @@ @@ -63,6 +63,9 @@
template <typename T>
class Matrix3;
template <typename T>
class Vector2;
template <typename T>
class Vector3
{
@ -189,6 +192,9 @@ public: @@ -189,6 +192,9 @@ public:
// rotate vector by angle in radians in xy plane leaving z untouched
void rotate_xy(float rotation_rad);
// return xy components of a vector3
Vector2<T> xy();
// gets the length of this vector squared
T length_squared() const
{

Loading…
Cancel
Save