mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: allow scaled passthru to go to trim on rc failsafe
This commit is contained in:
parent
2e1b7897fd
commit
53a4194297
@ -62,9 +62,14 @@ void RC_Channel_Rover::init_aux_function(const aux_func_t ch_option, const AuxSw
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
bool RC_Channels_Rover::in_rc_failsafe() const
|
||||||
|
{
|
||||||
|
return rover.failsafe.bits & FAILSAFE_EVENT_THROTTLE;
|
||||||
|
}
|
||||||
|
|
||||||
bool RC_Channels_Rover::has_valid_input() const
|
bool RC_Channels_Rover::has_valid_input() const
|
||||||
{
|
{
|
||||||
if (rover.failsafe.bits & FAILSAFE_EVENT_THROTTLE) {
|
if (in_rc_failsafe()) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
|
@ -32,6 +32,7 @@ class RC_Channels_Rover : public RC_Channels
|
|||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
|
bool in_rc_failsafe() const override;
|
||||||
bool has_valid_input() const override;
|
bool has_valid_input() 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