Plane: Fixing issue 302

Using the configured FS_THR_VALUE to check for failsafe instead of
just checking against 50 below throttle min.
This commit is contained in:
Grant Morphett 2015-09-04 11:39:39 +10:00 committed by Andrew Tridgell
parent f5c7ac7a00
commit a1b96f659b
1 changed files with 1 additions and 1 deletions

View File

@ -179,7 +179,7 @@ int8_t Plane::test_failsafe(uint8_t argc, const Menu::arg *argv)
fail_test++;
}
if(g.throttle_fs_enabled && channel_throttle->get_failsafe()) {
if(g.throttle_fs_enabled && (channel_throttle->radio_in < g.throttle_fs_value)) {
cliSerial->printf_P(PSTR("THROTTLE FAILSAFE ACTIVATED: %d, "), (int)channel_throttle->radio_in);
print_flight_mode(cliSerial, readSwitch());
cliSerial->println();