RC_Channel: allow scaled passthru to go to trim on rc failsafe

This commit is contained in:
Henry Wurzburg 2023-06-22 18:10:42 -05:00 committed by Peter Barker
parent 12527f0426
commit 5510dcc45d
1 changed files with 1 additions and 1 deletions

View File

@ -491,7 +491,7 @@ public:
void reset_mode_switch(); void reset_mode_switch();
virtual void read_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 bool has_valid_input() const { return false; };
virtual RC_Channel *get_arming_channel(void) const { return nullptr; }; virtual RC_Channel *get_arming_channel(void) const { return nullptr; };