mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
ArduCopter: allow scaled passthru to go to trim on rc failsafe
This commit is contained in:
parent
78e44ebf3a
commit
d0a0fd730c
@ -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
|
bool RC_Channels_Copter::has_valid_input() const
|
||||||
{
|
{
|
||||||
if (copter.failsafe.radio) {
|
if (in_rc_failsafe()) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (copter.failsafe.radio_counter != 0) {
|
if (copter.failsafe.radio_counter != 0) {
|
||||||
|
@ -31,6 +31,7 @@ class RC_Channels_Copter : public RC_Channels
|
|||||||
public:
|
public:
|
||||||
|
|
||||||
bool has_valid_input() const override;
|
bool has_valid_input() const override;
|
||||||
|
bool in_rc_failsafe() const override;
|
||||||
|
|
||||||
RC_Channel *get_arming_channel(void) const override;
|
RC_Channel *get_arming_channel(void) const override;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user