Blimp: 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 f59293c5a4
commit 2e1b7897fd
2 changed files with 6 additions and 0 deletions

View File

@ -36,6 +36,11 @@ void RC_Channel_Blimp::mode_switch_changed(modeswitch_pos_t new_pos)
}
}
bool RC_Channels_Blimp::in_rc_failsafe() const
{
return blimp.failsafe.radio;
}
bool RC_Channels_Blimp::has_valid_input() const
{
if (blimp.failsafe.radio) {

View File

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