mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Sub: Increase interval between failsafe warnings
This commit is contained in:
parent
8495384031
commit
83b75db6b0
@ -70,8 +70,8 @@ void Sub::failsafe_internal_pressure_check()
|
||||
failsafe.internal_pressure = true;
|
||||
}
|
||||
|
||||
// Warn every 5 seconds
|
||||
if (failsafe.internal_pressure && tnow > last_pressure_warn_ms + 5000) {
|
||||
// Warn every 30 seconds
|
||||
if (failsafe.internal_pressure && tnow > last_pressure_warn_ms + 30000) {
|
||||
last_pressure_warn_ms = tnow;
|
||||
gcs_send_text(MAV_SEVERITY_WARNING, "Internal pressure critical!");
|
||||
}
|
||||
@ -99,8 +99,8 @@ void Sub::failsafe_internal_temperature_check()
|
||||
failsafe.internal_temperature = true;
|
||||
}
|
||||
|
||||
// Warn every 5 seconds
|
||||
if (failsafe.internal_temperature && tnow > last_temperature_warn_ms + 5000) {
|
||||
// Warn every 30 seconds
|
||||
if (failsafe.internal_temperature && tnow > last_temperature_warn_ms + 30000) {
|
||||
last_temperature_warn_ms = tnow;
|
||||
gcs_send_text(MAV_SEVERITY_WARNING, "Internal temperature critical!");
|
||||
}
|
||||
@ -122,8 +122,8 @@ void Sub::set_leak_status(bool status)
|
||||
uint32_t tnow = AP_HAL::millis();
|
||||
|
||||
// We have a leak
|
||||
// Always send a warning every 5 seconds
|
||||
if (tnow > failsafe.last_leak_warn_ms + 5000) {
|
||||
// Always send a warning every 20 seconds
|
||||
if (tnow > failsafe.last_leak_warn_ms + 20000) {
|
||||
failsafe.last_leak_warn_ms = tnow;
|
||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "Leak Detected");
|
||||
}
|
||||
@ -168,8 +168,8 @@ void Sub::failsafe_gcs_check()
|
||||
// GCS heartbeat has timed out
|
||||
//////////////////////////////
|
||||
|
||||
// Send a warning every 5 seconds
|
||||
if (tnow > failsafe.last_gcs_warn_ms + 5000) {
|
||||
// Send a warning every 30 seconds
|
||||
if (tnow > failsafe.last_gcs_warn_ms + 30000) {
|
||||
failsafe.last_gcs_warn_ms = tnow;
|
||||
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "MYGCS: %d, heartbeat lost", g.sysid_my_gcs);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user