void Rover::control_failsafe(uint16_t pwm) { if (!g.fs_throttle_enabled) { // no throttle failsafe return; } // Check for failsafe condition based on loss of GCS control if (rc_override_active) { failsafe_trigger(FAILSAFE_EVENT_RC, (millis() - failsafe.rc_override_timer) > 1500); } else if (g.fs_throttle_enabled) { bool failed = pwm < static_cast<uint16_t>(g.fs_throttle_value); if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 2000) { failed = true; } failsafe_trigger(FAILSAFE_EVENT_THROTTLE, failed); } }
/* check for GCS failsafe - 10Hz */ void Rover::gcs_failsafe_check(void) { if (g.fs_gcs_enabled) { failsafe_trigger(FAILSAFE_EVENT_GCS, last_heartbeat_ms != 0 && (millis() - last_heartbeat_ms) > 2000); } }