AP_AdvancedFailsafe: move handling of last-seen-SYSID_MYGCS up to GCS base class

This commit is contained in:
Peter Barker 2021-02-05 13:28:07 +11:00 committed by Andrew Tridgell
parent 77998fb5ba
commit 5d686b9cb1
2 changed files with 3 additions and 2 deletions

View File

@ -164,7 +164,7 @@ const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = {
// check for Failsafe conditions. This is called at 10Hz by the main
// ArduPlane code
void
AP_AdvancedFailsafe::check(uint32_t last_heartbeat_ms, bool geofence_breached, uint32_t last_valid_rc_ms)
AP_AdvancedFailsafe::check(bool geofence_breached, uint32_t last_valid_rc_ms)
{
if (!_enable) {
return;
@ -203,6 +203,7 @@ AP_AdvancedFailsafe::check(uint32_t last_heartbeat_ms, bool geofence_breached, u
hal.gpio->write(_manual_pin, mode==AFS_MANUAL);
}
const uint32_t last_heartbeat_ms = gcs().sysid_myggcs_last_seen_time_ms();
uint32_t now = AP_HAL::millis();
bool gcs_link_ok = ((now - last_heartbeat_ms) < 10000);
bool gps_lock_ok = ((now - AP::gps().last_fix_time_ms()) < 3000);

View File

@ -75,7 +75,7 @@ public:
bool enabled() { return _enable; }
// check that everything is OK
void check(uint32_t last_heartbeat_ms, bool geofence_breached, uint32_t last_valid_rc_ms);
void check(bool geofence_breached, uint32_t last_valid_rc_ms);
// generate heartbeat msgs, so external failsafe boards are happy
// during sensor calibration