From 302e5c687183613a1f393acb348fddd71e291242 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 14 Dec 2017 13:09:59 +1100 Subject: [PATCH] AP_Common: have get_vector_xy_from_origin_NE take a Vector2f rather than 3f Also, rename it from get_vector_xy_from_origin_NED --- libraries/AP_Common/Location.cpp | 12 +++++++----- libraries/AP_Common/Location.h | 5 +++-- 2 files changed, 10 insertions(+), 7 deletions(-) diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index 7de5e3c97a..ebb15994c4 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -190,24 +190,26 @@ bool Location_Class::get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) co } } -bool Location_Class::get_vector_xy_from_origin_NEU(Vector3f &vec_neu) const +bool Location_Class::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const { - // convert to neu Location ekf_origin; if (!_ahrs->get_origin(ekf_origin)) { return false; } - vec_neu.x = (lat-ekf_origin.lat) * LATLON_TO_CM; - vec_neu.y = (lng-ekf_origin.lng) * LATLON_TO_CM * longitude_scale(ekf_origin); + vec_ne.x = (lat-ekf_origin.lat) * LATLON_TO_CM; + vec_ne.y = (lng-ekf_origin.lng) * LATLON_TO_CM * longitude_scale(ekf_origin); return true; } bool Location_Class::get_vector_from_origin_NEU(Vector3f &vec_neu) const { // convert lat, lon - if (!get_vector_xy_from_origin_NEU(vec_neu)) { + Vector2f vec_ne; + if (!get_vector_xy_from_origin_NE(vec_ne)) { return false; } + vec_neu.x = vec_ne.x; + vec_neu.y = vec_ne.y; // convert altitude int32_t alt_above_origin_cm = 0; diff --git a/libraries/AP_Common/Location.h b/libraries/AP_Common/Location.h index bfd61436ce..d7fee612f4 100644 --- a/libraries/AP_Common/Location.h +++ b/libraries/AP_Common/Location.h @@ -55,10 +55,11 @@ public: // the original frame or desired frame is above-terrain bool change_alt_frame(ALT_FRAME desired_frame); - // get position as a vector from home (x,y only or x,y,z) + // get position as a vector from origin (x,y only or x,y,z) // return false on failure to get the vector which can only // happen if the EKF origin has not been set yet - bool get_vector_xy_from_origin_NEU(Vector3f &vec_neu) const; + // x, y and z are in centimetres + bool get_vector_xy_from_origin_NE(Vector2f &vec_ne) const; bool get_vector_from_origin_NEU(Vector3f &vec_neu) const; // return distance in meters between two locations