diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 4e9d24a265..865052aae6 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -275,8 +275,10 @@ void SITL_State::_fdm_input_local(void) sitl_model->fill_fdm(_sitl->state); _sitl->update_rate_hz = sitl_model->get_rate_hz(); - for (uint8_t i=0; i< _sitl->state.rcin_chan_count; i++) { - pwm_input[i] = 1000 + _sitl->state.rcin[i]*1000; + if (_sitl->rc_fail == 0) { + for (uint8_t i=0; i< _sitl->state.rcin_chan_count; i++) { + pwm_input[i] = 1000 + _sitl->state.rcin[i]*1000; + } } }