From b625596dfa042a718f1f83020703c1aa1991f93f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 13 Feb 2021 14:46:34 +1100 Subject: [PATCH] AP_Common: use singleton to access AP_Terrain data --- libraries/AP_Common/Location.cpp | 8 +++++--- libraries/AP_Common/Location.h | 5 ----- 2 files changed, 5 insertions(+), 8 deletions(-) diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index 0290b4923f..3279b37f2d 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -7,8 +7,6 @@ #include #include -AP_Terrain *Location::_terrain = nullptr; - /// constructors Location::Location() { @@ -138,7 +136,11 @@ 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(*this, alt_terr_cm, true)) { + AP_Terrain *terrain = AP::terrain(); + if (terrain == nullptr) { + return false; + } + if (!terrain->height_amsl(*this, alt_terr_cm, true)) { return false; } // convert terrain alt to cm diff --git a/libraries/AP_Common/Location.h b/libraries/AP_Common/Location.h index 855c9a43f7..4c75c7cd2e 100644 --- a/libraries/AP_Common/Location.h +++ b/libraries/AP_Common/Location.h @@ -2,8 +2,6 @@ #include -class AP_Terrain; - #define LOCATION_ALT_MAX_M 83000 // maximum altitude (in meters) that can be fit into Location structure's alt field class Location @@ -35,8 +33,6 @@ public: Location(const Vector3f &ekf_offset_neu, AltFrame frame); Location(const Vector3d &ekf_offset_neu, AltFrame frame); - static void set_terrain(AP_Terrain* terrain) { _terrain = terrain; } - // set altitude void set_alt_cm(int32_t alt_cm, AltFrame frame); @@ -134,7 +130,6 @@ public: static int32_t diff_longitude(int32_t lon1, int32_t lon2); private: - static AP_Terrain *_terrain; // scaling factor from 1e-7 degrees to meters at equator // == 1.0e-7 * DEG_TO_RAD * RADIUS_OF_EARTH