mirror of https://github.com/ArduPilot/ardupilot
Blimp: allow scaled passthru to go to trim on rc failsafe
This commit is contained in:
parent
f59293c5a4
commit
2e1b7897fd
|
@ -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) {
|
||||
|
|
|
@ -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;
|
||||
|
||||
|
|
Loading…
Reference in New Issue