mirror of https://github.com/ArduPilot/ardupilot
Plane: Remove redundant protection
This commit is contained in:
parent
851ee24c99
commit
ea64077f77
|
@ -278,36 +278,34 @@ void Plane::control_failsafe()
|
|||
}
|
||||
}
|
||||
|
||||
if(g.throttle_fs_enabled == 0)
|
||||
if(g.throttle_fs_enabled == 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (g.throttle_fs_enabled) {
|
||||
if (rc_failsafe_active()) {
|
||||
// we detect a failsafe from radio
|
||||
// throttle has dropped below the mark
|
||||
failsafe.throttle_counter++;
|
||||
if (failsafe.throttle_counter == 10) {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Throttle failsafe on");
|
||||
failsafe.rc_failsafe = true;
|
||||
AP_Notify::flags.failsafe_radio = true;
|
||||
}
|
||||
if (failsafe.throttle_counter > 10) {
|
||||
failsafe.throttle_counter = 10;
|
||||
}
|
||||
|
||||
}else if(failsafe.throttle_counter > 0) {
|
||||
// we are no longer in failsafe condition
|
||||
// but we need to recover quickly
|
||||
failsafe.throttle_counter--;
|
||||
if (failsafe.throttle_counter > 3) {
|
||||
failsafe.throttle_counter = 3;
|
||||
}
|
||||
if (failsafe.throttle_counter == 1) {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Throttle failsafe off");
|
||||
} else if(failsafe.throttle_counter == 0) {
|
||||
failsafe.rc_failsafe = false;
|
||||
AP_Notify::flags.failsafe_radio = false;
|
||||
}
|
||||
if (rc_failsafe_active()) {
|
||||
// we detect a failsafe from radio
|
||||
// throttle has dropped below the mark
|
||||
failsafe.throttle_counter++;
|
||||
if (failsafe.throttle_counter == 10) {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Throttle failsafe on");
|
||||
failsafe.rc_failsafe = true;
|
||||
AP_Notify::flags.failsafe_radio = true;
|
||||
}
|
||||
if (failsafe.throttle_counter > 10) {
|
||||
failsafe.throttle_counter = 10;
|
||||
}
|
||||
} else if(failsafe.throttle_counter > 0) {
|
||||
// we are no longer in failsafe condition
|
||||
// but we need to recover quickly
|
||||
failsafe.throttle_counter--;
|
||||
if (failsafe.throttle_counter > 3) {
|
||||
failsafe.throttle_counter = 3;
|
||||
}
|
||||
if (failsafe.throttle_counter == 1) {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Throttle failsafe off");
|
||||
} else if(failsafe.throttle_counter == 0) {
|
||||
failsafe.rc_failsafe = false;
|
||||
AP_Notify::flags.failsafe_radio = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue