mirror of https://github.com/ArduPilot/ardupilot
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:
parent
a7a27d62a0
commit
2f0e9addcb
|
@ -18,7 +18,7 @@ int8_t RC_Channels_Plane::flight_mode_channel_number() const
|
||||||
|
|
||||||
bool RC_Channels_Plane::has_valid_input() 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;
|
return false;
|
||||||
}
|
}
|
||||||
if (plane.failsafe.throttle_counter != 0) {
|
if (plane.failsafe.throttle_counter != 0) {
|
||||||
|
|
Loading…
Reference in New Issue