From fe4abc521a716611a63383cd2b142cedcee0e437 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 21 Jun 2021 17:25:51 +1000 Subject: [PATCH] AP_Math: make vector3 xy() method return a reference --- libraries/AP_Math/vector3.cpp | 7 ------- libraries/AP_Math/vector3.h | 12 +++++++++--- 2 files changed, 9 insertions(+), 10 deletions(-) diff --git a/libraries/AP_Math/vector3.cpp b/libraries/AP_Math/vector3.cpp index 921c852ed7..71ffc08944 100644 --- a/libraries/AP_Math/vector3.cpp +++ b/libraries/AP_Math/vector3.cpp @@ -617,13 +617,6 @@ bool Vector3::segment_plane_intersect(const Vector3& seg_start, const Vect return true; } -// return xy components of a vector3 -template -Vector2 Vector3::xy() -{ - return Vector2{x,y}; -} - // define for float and double template class Vector3; template class Vector3; diff --git a/libraries/AP_Math/vector3.h b/libraries/AP_Math/vector3.h index 150c040332..d3ac153eab 100644 --- a/libraries/AP_Math/vector3.h +++ b/libraries/AP_Math/vector3.h @@ -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 xy(); - + // return xy components of a vector3 as a vector2. + // this returns a reference to the original vector3 xy data + const Vector2 &xy() const { + return *(const Vector2 *)this; + } + Vector2 &xy() { + return *(Vector2 *)this; + } + // gets the length of this vector squared T length_squared() const {