Browse Source

AP_Math: make vector3 xy() method return a reference

c415-sdk
Andrew Tridgell 4 years ago
parent
commit
fe4abc521a
  1. 7
      libraries/AP_Math/vector3.cpp
  2. 12
      libraries/AP_Math/vector3.h

7
libraries/AP_Math/vector3.cpp

@ -617,13 +617,6 @@ bool Vector3<T>::segment_plane_intersect(const Vector3<T>& seg_start, const Vect @@ -617,13 +617,6 @@ 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>;

12
libraries/AP_Math/vector3.h

@ -192,9 +192,15 @@ public: @@ -192,9 +192,15 @@ 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();
// return xy components of a vector3 as a vector2.
// this returns a reference to the original vector3 xy data
const Vector2<T> &xy() const {
return *(const Vector2<T> *)this;
}
Vector2<T> &xy() {
return *(Vector2<T> *)this;
}
// gets the length of this vector squared
T length_squared() const
{

Loading…
Cancel
Save