SITL: fix simulated RC failure while receiving RC overrides

This commit is contained in:
Jeffrey Laut 2022-09-01 07:34:45 -04:00 committed by Peter Barker
parent 2165d19af1
commit 3133aff352
1 changed files with 5 additions and 0 deletions

View File

@ -441,6 +441,11 @@ bool SITL_State::_read_rc_sitl_input()
const ssize_t size = _sitl_rc_in.recv(&pwm_pkt, sizeof(pwm_pkt), 0);
// if we are simulating no pulses RC failure, do not update pwm_input
if (_sitl->rc_fail == SITL::SIM::SITL_RCFail_NoPulses) {
return size != -1; // we must continue to drain _sitl_rc
}
if (_sitl->rc_fail == SITL::SIM::SITL_RCFail_Throttle950) {
// discard anything we just read from the "receiver" and set
// values to bind values: