diff --git a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp index d7fc3e9439..92f23b24d9 100644 --- a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp +++ b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp @@ -325,6 +325,7 @@ AP_AdvancedFailsafe::check_altlimit(void) } // see if the barometer is dead + const AP_Baro &baro = AP::baro(); if (AP_HAL::millis() - baro.get_last_update() > 5000) { // the barometer has been unresponsive for 5 seconds. See if we can switch to GPS if (_amsl_margin_gps != -1 && diff --git a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h index 36c7e22129..1664b70805 100644 --- a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h +++ b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h @@ -51,9 +51,8 @@ public: }; // Constructor - AP_AdvancedFailsafe(AP_Mission &_mission, AP_Baro &_baro, const AP_GPS &_gps, const RCMapper &_rcmap) : + AP_AdvancedFailsafe(AP_Mission &_mission, const AP_GPS &_gps, const RCMapper &_rcmap) : mission(_mission), - baro(_baro), gps(_gps), rcmap(_rcmap), _gps_loss_count(0), @@ -96,7 +95,6 @@ protected: enum state _state; AP_Mission &mission; - AP_Baro &baro; const AP_GPS &gps; const RCMapper &rcmap;