From 1a853f6f822d8b27bd5614d21c83be16b5700ae6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 7 Nov 2018 19:28:27 +1100 Subject: [PATCH] AP_Terrain: use ahrs singleton --- libraries/AP_Terrain/AP_Terrain.cpp | 15 ++++++++++----- libraries/AP_Terrain/AP_Terrain.h | 6 +----- libraries/AP_Terrain/TerrainGCS.cpp | 3 ++- 3 files changed, 13 insertions(+), 11 deletions(-) diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index bed36dc563..3f5ba26c31 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -56,8 +56,7 @@ const AP_Param::GroupInfo AP_Terrain::var_info[] = { }; // constructor -AP_Terrain::AP_Terrain(AP_AHRS &_ahrs, const AP_Mission &_mission, const AP_Rally &_rally) : - ahrs(_ahrs), +AP_Terrain::AP_Terrain(const AP_Mission &_mission, const AP_Rally &_rally) : mission(_mission), rally(_rally), disk_io_state(DiskIoIdle), @@ -81,6 +80,8 @@ bool AP_Terrain::height_amsl(const Location &loc, float &height, bool corrected) return false; } + const AP_AHRS &ahrs = AP::ahrs(); + // quick access for home altitude if (loc.lat == home_loc.lat && loc.lng == home_loc.lng) { @@ -161,6 +162,8 @@ bool AP_Terrain::height_amsl(const Location &loc, float &height, bool corrected) */ bool AP_Terrain::height_terrain_difference_home(float &terrain_difference, bool extrapolate) { + const AP_AHRS &ahrs = AP::ahrs(); + float height_home, height_loc; if (!height_amsl(ahrs.get_home(), height_home, false)) { // we don't know the height of home @@ -208,7 +211,7 @@ bool AP_Terrain::height_above_terrain(float &terrain_altitude, bool extrapolate) } float relative_home_altitude; - ahrs.get_relative_position_D_home(relative_home_altitude); + AP::ahrs().get_relative_position_D_home(relative_home_altitude); relative_home_altitude = -relative_home_altitude; terrain_altitude = relative_home_altitude - terrain_difference; @@ -254,7 +257,7 @@ float AP_Terrain::lookahead(float bearing, float distance, float climb_ratio) } Location loc; - if (!ahrs.get_position(loc)) { + if (!AP::ahrs().get_position(loc)) { // we don't know where we are return 0; } @@ -295,6 +298,8 @@ void AP_Terrain::update(void) // just schedule any needed disk IO schedule_disk_io(); + const AP_AHRS &ahrs = AP::ahrs(); + // try to ensure the home location is populated float height; height_amsl(ahrs.get_home(), height, false); @@ -342,7 +347,7 @@ void AP_Terrain::log_terrain_data(DataFlash_Class &dataflash) return; } Location loc; - if (!ahrs.get_position(loc)) { + if (!AP::ahrs().get_position(loc)) { // we don't know where we are return; } diff --git a/libraries/AP_Terrain/AP_Terrain.h b/libraries/AP_Terrain/AP_Terrain.h index a5608c69b6..bcaad7dcdb 100644 --- a/libraries/AP_Terrain/AP_Terrain.h +++ b/libraries/AP_Terrain/AP_Terrain.h @@ -76,7 +76,7 @@ class AP_Terrain { public: - AP_Terrain(AP_AHRS &_ahrs, const AP_Mission &_mission, const AP_Rally &_rally); + AP_Terrain(const AP_Mission &_mission, const AP_Rally &_rally); /* Do not allow copies */ AP_Terrain(const AP_Terrain &other) = delete; @@ -336,10 +336,6 @@ private: AP_Int8 enable; AP_Int16 grid_spacing; // meters between grid points - // reference to AHRS, so we can ask for our position, - // heading and speed - AP_AHRS &ahrs; - // reference to AP_Mission, so we can ask preload terrain data for // all waypoints const AP_Mission &mission; diff --git a/libraries/AP_Terrain/TerrainGCS.cpp b/libraries/AP_Terrain/TerrainGCS.cpp index d23139ed04..5cae98062f 100644 --- a/libraries/AP_Terrain/TerrainGCS.cpp +++ b/libraries/AP_Terrain/TerrainGCS.cpp @@ -92,7 +92,7 @@ void AP_Terrain::send_request(mavlink_channel_t chan) schedule_disk_io(); Location loc; - if (!ahrs.get_position(loc)) { + if (!AP::ahrs().get_position(loc)) { // we don't know where we are return; } @@ -206,6 +206,7 @@ void AP_Terrain::send_terrain_report(mavlink_channel_t chan, const Location &loc float home_terrain_height = 0; uint16_t spacing = 0; Location current_loc; + const AP_AHRS &ahrs = AP::ahrs(); if (ahrs.get_position(current_loc) && height_amsl(ahrs.get_home(), home_terrain_height, false) && height_amsl(loc, terrain_height, false)) {