mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
RC_Channel: Cope with selective overrides and no RC reciever in a healthier way
This commit is contained in:
parent
e02145efa0
commit
e4d0484b75
@ -135,7 +135,7 @@ bool RC_Channel::update(void)
|
||||
{
|
||||
if (has_override() && !rc().ignore_overrides()) {
|
||||
radio_in = override_value;
|
||||
} else if (!rc().ignore_receiver()) {
|
||||
} else if (rc().has_had_rc_receiver() && !rc().ignore_receiver()) {
|
||||
radio_in = hal.rcin->read(ch_in);
|
||||
} else {
|
||||
return false;
|
||||
|
@ -401,7 +401,10 @@ public:
|
||||
float override_timeout_ms() const {
|
||||
return _override_timeout.get() * 1e3f;
|
||||
}
|
||||
|
||||
|
||||
// returns true if we have had a direct detach RC reciever, does not include overrides
|
||||
bool has_had_rc_receiver() const { return _has_had_rc_receiver; }
|
||||
|
||||
/*
|
||||
get the RC input PWM value given a channel number. Note that
|
||||
channel numbers start at 1, as this API is designed for use in
|
||||
@ -435,6 +438,7 @@ private:
|
||||
|
||||
uint32_t last_update_ms;
|
||||
bool has_new_overrides;
|
||||
bool _has_had_rc_receiver; // true if we have had a direct detach RC reciever, does not include overrides
|
||||
|
||||
AP_Float _override_timeout;
|
||||
AP_Int32 _options;
|
||||
|
@ -68,7 +68,9 @@ uint8_t RC_Channels::get_radio_in(uint16_t *chans, const uint8_t num_channels)
|
||||
// update all the input channels
|
||||
bool RC_Channels::read_input(void)
|
||||
{
|
||||
if (!hal.rcin->new_input() && !has_new_overrides) {
|
||||
if (hal.rcin->new_input()) {
|
||||
_has_had_rc_receiver = true;
|
||||
} else if (!has_new_overrides) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user