Plane: set failsafe_radio AP_Notify bits

This commit is contained in:
Andrew Tridgell 2013-09-18 11:58:54 +10:00
parent 150e7a3f16
commit 8a76d82de4
1 changed files with 4 additions and 0 deletions

View File

@ -121,8 +121,10 @@ static void control_failsafe(uint16_t pwm)
if (failsafe.rc_override_active) {
if (millis() - failsafe.last_heartbeat_ms > g.short_fs_timeout*1000) {
failsafe.ch3_failsafe = true;
AP_Notify::flags.failsafe_radio = true;
} else {
failsafe.ch3_failsafe = false;
AP_Notify::flags.failsafe_radio = false;
}
//Check for failsafe and debounce funky reads
@ -134,6 +136,7 @@ static void control_failsafe(uint16_t pwm)
if (failsafe.ch3_counter == 10) {
gcs_send_text_fmt(PSTR("MSG FS ON %u"), (unsigned)pwm);
failsafe.ch3_failsafe = true;
AP_Notify::flags.failsafe_radio = true;
}
if (failsafe.ch3_counter > 10) {
failsafe.ch3_counter = 10;
@ -150,6 +153,7 @@ static void control_failsafe(uint16_t pwm)
gcs_send_text_fmt(PSTR("MSG FS OFF %u"), (unsigned)pwm);
} else if(failsafe.ch3_counter == 0) {
failsafe.ch3_failsafe = false;
AP_Notify::flags.failsafe_radio = false;
}
}
}