ArduCopter: 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 78e44ebf3a
commit d0a0fd730c
2 changed files with 7 additions and 1 deletions

View File

@ -37,9 +37,14 @@ void RC_Channel_Copter::mode_switch_changed(modeswitch_pos_t new_pos)
}
}
bool RC_Channels_Copter::in_rc_failsafe() const
{
return copter.failsafe.radio;
}
bool RC_Channels_Copter::has_valid_input() const
{
if (copter.failsafe.radio) {
if (in_rc_failsafe()) {
return false;
}
if (copter.failsafe.radio_counter != 0) {

View File

@ -31,6 +31,7 @@ class RC_Channels_Copter : public RC_Channels
public:
bool has_valid_input() const override;
bool in_rc_failsafe() const override;
RC_Channel *get_arming_channel(void) const override;