mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed throttle failsafe with reversed throttle
This commit is contained in:
parent
e32e83f2f0
commit
56f574684d
|
@ -43,8 +43,7 @@ static bool stick_mixing_enabled(void)
|
|||
if (g.stick_mixing != STICK_MIXING_DISABLED &&
|
||||
geofence_stickmixing() &&
|
||||
failsafe.state == FAILSAFE_NONE &&
|
||||
(g.throttle_fs_enabled == 0 ||
|
||||
channel_throttle->radio_in >= g.throttle_fs_value)) {
|
||||
!throttle_failsafe_level()) {
|
||||
// we're in an auto mode, and haven't triggered failsafe
|
||||
return true;
|
||||
} else {
|
||||
|
|
|
@ -129,7 +129,7 @@ static void control_failsafe(uint16_t pwm)
|
|||
|
||||
//Check for failsafe and debounce funky reads
|
||||
} else if (g.throttle_fs_enabled) {
|
||||
if (pwm < (unsigned)g.throttle_fs_value) {
|
||||
if (throttle_failsafe_level()) {
|
||||
// we detect a failsafe from radio
|
||||
// throttle has dropped below the mark
|
||||
failsafe.ch3_counter++;
|
||||
|
@ -221,3 +221,17 @@ static void trim_radio()
|
|||
|
||||
trim_control_surfaces();
|
||||
}
|
||||
|
||||
/*
|
||||
return true if throttle level is below throttle failsafe threshold
|
||||
*/
|
||||
static bool throttle_failsafe_level(void)
|
||||
{
|
||||
if (!g.throttle_fs_enabled) {
|
||||
return false;
|
||||
}
|
||||
if (channel_throttle->get_reverse()) {
|
||||
return channel_throttle->radio_in >= g.throttle_fs_value;
|
||||
}
|
||||
return channel_throttle->radio_in <= g.throttle_fs_value;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue