From 5510dcc45d7c27424b8b34d56aee460f54cb114a Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Thu, 22 Jun 2023 18:10:42 -0500 Subject: [PATCH] RC_Channel: allow scaled passthru to go to trim on rc failsafe --- libraries/RC_Channel/RC_Channel.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 257fb98ccc..871b3affda 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -491,7 +491,7 @@ public: void reset_mode_switch(); virtual void read_mode_switch(); - // has_valid_input should be pure-virtual when Plane is converted + virtual bool in_rc_failsafe() const { return true; }; virtual bool has_valid_input() const { return false; }; virtual RC_Channel *get_arming_channel(void) const { return nullptr; };