From 72f485b5a5148964baf3a4838287e32c220b21fb Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 6 Sep 2023 17:21:13 +1000 Subject: [PATCH] AP_Common: remove unused Location constructor from Vector3d Replaced with AHRS method --- libraries/AP_Common/Location.cpp | 16 ---------------- 1 file changed, 16 deletions(-) diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index 31c44e3307..e961309438 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -49,22 +49,6 @@ Location::Location(const Vector3f &ekf_offset_neu, AltFrame frame) } } -Location::Location(const Vector3d &ekf_offset_neu, AltFrame frame) -{ - zero(); - - // store alt and alt frame - set_alt_cm(ekf_offset_neu.z, frame); - - // calculate lat, lon - Location ekf_origin; - if (AP::ahrs().get_origin(ekf_origin)) { - lat = ekf_origin.lat; - lng = ekf_origin.lng; - offset(ekf_offset_neu.x * 0.01, ekf_offset_neu.y * 0.01); - } -} - void Location::set_alt_cm(int32_t alt_cm, AltFrame frame) { alt = alt_cm;