From 979d8109129f778794a01825d4f11ddc4a11288f Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Thu, 22 Jun 2023 18:10:42 -0500 Subject: [PATCH] ArduPlane: allow scaled passthru to go to trim on rc failsafe --- ArduPlane/RC_Channel.cpp | 7 ++++++- ArduPlane/RC_Channel.h | 1 + 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index 88c24cb4e4..e476982eb8 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -16,9 +16,14 @@ int8_t RC_Channels_Plane::flight_mode_channel_number() const return plane.g.flight_mode_channel.get(); } +bool RC_Channels_Plane::in_rc_failsafe() const +{ + return (plane.rc_failsafe_active() || plane.failsafe.rc_failsafe); +} + bool RC_Channels_Plane::has_valid_input() const { - if (plane.rc_failsafe_active() || plane.failsafe.rc_failsafe) { + if (in_rc_failsafe()) { return false; } if (plane.failsafe.throttle_counter != 0) { diff --git a/ArduPlane/RC_Channel.h b/ArduPlane/RC_Channel.h index a65f8bb335..7ecc352c32 100644 --- a/ArduPlane/RC_Channel.h +++ b/ArduPlane/RC_Channel.h @@ -45,6 +45,7 @@ public: return &obj_channels[chan]; } + bool in_rc_failsafe() const override; bool has_valid_input() const override; RC_Channel *get_arming_channel(void) const override;