ArduPlane: allow scaled passthru to go to trim on rc failsafe
This commit is contained in:
parent
d0a0fd730c
commit
979d810912
@ -16,9 +16,14 @@ int8_t RC_Channels_Plane::flight_mode_channel_number() const
|
||||
return plane.g.flight_mode_channel.get();
|
||||
}
|
||||
|
||||
bool RC_Channels_Plane::in_rc_failsafe() const
|
||||
{
|
||||
return (plane.rc_failsafe_active() || plane.failsafe.rc_failsafe);
|
||||
}
|
||||
|
||||
bool RC_Channels_Plane::has_valid_input() const
|
||||
{
|
||||
if (plane.rc_failsafe_active() || plane.failsafe.rc_failsafe) {
|
||||
if (in_rc_failsafe()) {
|
||||
return false;
|
||||
}
|
||||
if (plane.failsafe.throttle_counter != 0) {
|
||||
|
@ -45,6 +45,7 @@ public:
|
||||
return &obj_channels[chan];
|
||||
}
|
||||
|
||||
bool in_rc_failsafe() const override;
|
||||
bool has_valid_input() const override;
|
||||
|
||||
RC_Channel *get_arming_channel(void) const override;
|
||||
|
Loading…
Reference in New Issue
Block a user