AP_AdvancedFailsafe: use fence singleton in afs check

This commit is contained in:
Peter Barker 2022-10-21 12:25:52 +11:00 committed by Andrew Tridgell
parent 55aed98f81
commit ad0df546a7
2 changed files with 7 additions and 4 deletions

View File

@ -165,21 +165,24 @@ 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(bool geofence_breached, uint32_t last_valid_rc_ms)
{
AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms)
{
if (!_enable) {
return;
}
#if AP_FENCE_ENABLED
// we always check for fence breach
if(_enable_geofence_fs) {
if (geofence_breached || check_altlimit()) {
const AC_Fence *ap_fence = AP::fence();
if ((ap_fence != nullptr && ap_fence->get_breaches() != 0) || check_altlimit()) {
if (!_terminate) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to fence breach");
_terminate.set_and_notify(1);
}
}
}
#endif
// update max range check
max_range_update();

View File

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