mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Rover: 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:
parent
dd22b19ddd
commit
f5c7ac7a00
@ -171,7 +171,7 @@ int8_t Rover::test_failsafe(uint8_t argc, const Menu::arg *argv)
|
||||
fail_test++;
|
||||
}
|
||||
|
||||
if (g.fs_throttle_enabled && channel_throttle->get_failsafe()){
|
||||
if(g.fs_throttle_enabled && (channel_throttle->radio_in < g.fs_throttle_value)) {
|
||||
cliSerial->printf_P(PSTR("THROTTLE FAILSAFE ACTIVATED: %d, "), channel_throttle->radio_in);
|
||||
print_mode(cliSerial, readSwitch());
|
||||
cliSerial->println();
|
||||
|
Loading…
Reference in New Issue
Block a user