From 4abf854c452b42cdebda80451e88c3f5a6405ad7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 8 Jun 2021 09:31:58 +1000 Subject: [PATCH] AP_Common: remove weird cast of location object --- libraries/AP_Common/Location.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index bf7d5e702f..7d2b219fc1 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -120,7 +120,7 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const float alt_terr_cm = 0; if (frame == AltFrame::ABOVE_TERRAIN || desired_frame == AltFrame::ABOVE_TERRAIN) { #if AP_TERRAIN_AVAILABLE - if (_terrain == nullptr || !_terrain->height_amsl(*(Location *)this, alt_terr_cm, true)) { + if (_terrain == nullptr || !_terrain->height_amsl(*this, alt_terr_cm, true)) { return false; } // convert terrain alt to cm