Plane: fixed bug in RC_Channel::has_valid_input

needs to go false when no RCIN and THR_FAILSAFE=2. This prevents ICE
library from using RC input
This commit is contained in:
Andrew Tridgell 2020-09-26 10:23:23 +10:00
parent a7a27d62a0
commit 2f0e9addcb
1 changed files with 1 additions and 1 deletions

View File

@ -18,7 +18,7 @@ int8_t RC_Channels_Plane::flight_mode_channel_number() const
bool RC_Channels_Plane::has_valid_input() const
{
if (plane.failsafe.rc_failsafe) {
if (plane.rc_failsafe_active() || plane.failsafe.rc_failsafe) {
return false;
}
if (plane.failsafe.throttle_counter != 0) {