diff --git a/libraries/AP_HAL_SITL/RCInput.cpp b/libraries/AP_HAL_SITL/RCInput.cpp index 9b7b228091..0f6bdaa684 100644 --- a/libraries/AP_HAL_SITL/RCInput.cpp +++ b/libraries/AP_HAL_SITL/RCInput.cpp @@ -9,7 +9,6 @@ extern const AP_HAL::HAL& hal; void RCInput::init() { - clear_overrides(); } bool RCInput::new_input() @@ -26,9 +25,6 @@ uint16_t RCInput::read(uint8_t ch) if (ch >= SITL_RC_INPUT_CHANNELS) { return 0; } - if (_override[ch]) { - return _override[ch]; - } return _sitlState->pwm_input[ch]; } @@ -43,22 +39,4 @@ uint8_t RCInput::read(uint16_t* periods, uint8_t len) return len; } -bool RCInput::set_override(uint8_t channel, int16_t override) -{ - if (override < 0) { - return false; /* -1: no change. */ - } - if (channel < SITL_RC_INPUT_CHANNELS) { - _override[channel] = static_cast(override); - if (override != 0) { - return true; - } - } - return false; -} - -void RCInput::clear_overrides() -{ - memset(_override, 0, sizeof(_override)); -} #endif diff --git a/libraries/AP_HAL_SITL/RCInput.h b/libraries/AP_HAL_SITL/RCInput.h index 8c2309fb63..21f8ae7099 100644 --- a/libraries/AP_HAL_SITL/RCInput.h +++ b/libraries/AP_HAL_SITL/RCInput.h @@ -18,14 +18,8 @@ public: uint16_t read(uint8_t ch) override; uint8_t read(uint16_t* periods, uint8_t len) override; - bool set_override(uint8_t channel, int16_t override) override; - void clear_overrides() override; - private: SITL_State *_sitlState; - - /* override state */ - uint16_t _override[SITL_RC_INPUT_CHANNELS]; }; #endif