diff --git a/libraries/AP_HAL/SIMState.cpp b/libraries/AP_HAL/SIMState.cpp index 54d08a886ebcaa..e03cde7a663da6 100644 --- a/libraries/AP_HAL/SIMState.cpp +++ b/libraries/AP_HAL/SIMState.cpp @@ -125,12 +125,6 @@ void SIMState::fdm_input_local(void) } if (_sitl) { sitl_model->fill_fdm(_sitl->state); - - if (_sitl->rc_fail == SITL::SIM::SITL_RCFail_None) { - for (uint8_t i=0; i< _sitl->state.rcin_chan_count; i++) { - pwm_input[i] = 1000 + _sitl->state.rcin[i]*1000; - } - } } // output JSON state to ride along flight controllers diff --git a/libraries/AP_HAL/SIMState.h b/libraries/AP_HAL/SIMState.h index 0e1d2c808d0d0d..0c84791f91ea39 100644 --- a/libraries/AP_HAL/SIMState.h +++ b/libraries/AP_HAL/SIMState.h @@ -93,9 +93,6 @@ class AP_HAL::SIMState { pid_t _parent_pid; uint32_t _update_count; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - SocketAPM_native _sitl_rc_in{true}; -#endif SITL::SIM *_sitl; uint16_t _rcin_port; uint16_t _fg_view_port;