Plane: Using the existing function to check for throttle failsafe

No need to duplicate the code if we have an existing function for this
sort of thing.
This commit is contained in:
Grant Morphett 2015-09-07 13:52:22 +10:00 committed by Andrew Tridgell
parent 571b4478fd
commit c5c74eebfc

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->radio_in < g.throttle_fs_value)) {
if(rc_failsafe_active()) {
cliSerial->printf_P(PSTR("THROTTLE FAILSAFE ACTIVATED: %d, "), (int)channel_throttle->radio_in);
print_flight_mode(cliSerial, readSwitch());
cliSerial->println();