mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: allow scaled passthru to go to trim on rc failsafe
This commit is contained in:
parent
12527f0426
commit
5510dcc45d
|
@ -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; };
|
||||
|
|
Loading…
Reference in New Issue