AC_WPNav: use singleton to access AP_Terrain data

This commit is contained in:
Peter Barker 2021-02-13 14:46:34 +11:00 committed by Andrew Tridgell
parent 9ff77d8f1c
commit 2d28c1065e
2 changed files with 5 additions and 6 deletions

View File

@ -103,7 +103,8 @@ AC_WPNav::TerrainSource AC_WPNav::get_terrain_source() const
return AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER; return AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER;
} }
#if AP_TERRAIN_AVAILABLE #if AP_TERRAIN_AVAILABLE
if ((_terrain != nullptr) && _terrain->enabled()) { const AP_Terrain *terrain = AP::terrain();
if (terrain != nullptr && terrain->enabled()) {
return AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE; return AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE;
} else { } else {
return AC_WPNav::TerrainSource::TERRAIN_UNAVAILABLE; return AC_WPNav::TerrainSource::TERRAIN_UNAVAILABLE;
@ -576,7 +577,9 @@ bool AC_WPNav::get_terrain_offset(float& offset_cm)
case AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE: case AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE:
#if AP_TERRAIN_AVAILABLE #if AP_TERRAIN_AVAILABLE
float terr_alt = 0.0f; float terr_alt = 0.0f;
if (_terrain != nullptr && _terrain->height_above_terrain(terr_alt, true)) { AP_Terrain *terrain = AP::terrain();
if (terrain != nullptr &&
terrain->height_above_terrain(terr_alt, true)) {
offset_cm = _inav.get_altitude() - (terr_alt * 100.0f); offset_cm = _inav.get_altitude() - (terr_alt * 100.0f);
return true; return true;
} }

View File

@ -31,9 +31,6 @@ public:
/// Constructor /// Constructor
AC_WPNav(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control); AC_WPNav(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control);
/// provide pointer to terrain database
void set_terrain(AP_Terrain* terrain_ptr) { _terrain = terrain_ptr; }
/// provide rangefinder altitude /// provide rangefinder altitude
void set_rangefinder_alt(bool use, bool healthy, float alt_cm) { _rangefinder_available = use; _rangefinder_healthy = healthy; _rangefinder_alt_cm = alt_cm; } void set_rangefinder_alt(bool use, bool healthy, float alt_cm) { _rangefinder_available = use; _rangefinder_healthy = healthy; _rangefinder_alt_cm = alt_cm; }
@ -230,7 +227,6 @@ protected:
const AP_AHRS_View& _ahrs; const AP_AHRS_View& _ahrs;
AC_PosControl& _pos_control; AC_PosControl& _pos_control;
const AC_AttitudeControl& _attitude_control; const AC_AttitudeControl& _attitude_control;
AP_Terrain *_terrain;
// parameters // parameters
AP_Float _wp_speed_cms; // default maximum horizontal speed in cm/s during missions AP_Float _wp_speed_cms; // default maximum horizontal speed in cm/s during missions