diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index ea71cdb239..cf7da982bc 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -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; diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 9ba7dd34b6..e825e19e91 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -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; diff --git a/libraries/RC_Channel/RC_Channels.cpp b/libraries/RC_Channel/RC_Channels.cpp index 0f87ce7298..b70eccdf42 100644 --- a/libraries/RC_Channel/RC_Channels.cpp +++ b/libraries/RC_Channel/RC_Channels.cpp @@ -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; }