AP_AdvancedFailsafe: Use AP_GPS singleton

This commit is contained in:
Michael du Breuil 2019-06-13 20:13:31 -07:00 committed by Andrew Tridgell
parent 157a3b1e34
commit 3194b073ca
2 changed files with 5 additions and 8 deletions

View File

@ -24,6 +24,7 @@
#include <RC_Channel/RC_Channel.h>
#include <SRV_Channel/SRV_Channel.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_GPS/AP_GPS.h>
extern const AP_HAL::HAL& hal;
@ -189,7 +190,7 @@ AP_AdvancedFailsafe::check(uint32_t last_heartbeat_ms, bool geofence_breached, u
uint32_t now = AP_HAL::millis();
bool gcs_link_ok = ((now - last_heartbeat_ms) < 10000);
bool gps_lock_ok = ((now - gps.last_fix_time_ms()) < 3000);
bool gps_lock_ok = ((now - AP::gps().last_fix_time_ms()) < 3000);
switch (_state) {
case STATE_PREFLIGHT:
@ -324,6 +325,7 @@ AP_AdvancedFailsafe::check_altlimit(void)
// see if the barometer is dead
const AP_Baro &baro = AP::baro();
const AP_GPS &gps = AP::gps();
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 &&

View File

@ -24,7 +24,6 @@
#include <AP_Param/AP_Param.h>
#include <AP_Mission/AP_Mission.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_RCMapper/AP_RCMapper.h>
#include <inttypes.h>
@ -51,11 +50,8 @@ public:
};
// Constructor
AP_AdvancedFailsafe(AP_Mission &_mission, const AP_GPS &_gps) :
mission(_mission),
gps(_gps),
_gps_loss_count(0),
_comms_loss_count(0)
AP_AdvancedFailsafe(AP_Mission &_mission) :
mission(_mission)
{
AP_Param::setup_object_defaults(this, var_info);
@ -100,7 +96,6 @@ protected:
enum state _state;
AP_Mission &mission;
const AP_GPS &gps;
AP_Int8 _enable;
// digital output pins for communicating with the failsafe board