From dc4f1786f68ed32b9bb70b91d4b247f920f67272 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Thu, 26 Apr 2018 16:16:13 -0700 Subject: [PATCH] AP_HAL_F4Light: Remove RC overrides --- libraries/AP_HAL_F4Light/RCInput.cpp | 34 ---------------------------- libraries/AP_HAL_F4Light/RCInput.h | 7 ------ 2 files changed, 41 deletions(-) diff --git a/libraries/AP_HAL_F4Light/RCInput.cpp b/libraries/AP_HAL_F4Light/RCInput.cpp index dc2e295e24..6cfad99245 100644 --- a/libraries/AP_HAL_F4Light/RCInput.cpp +++ b/libraries/AP_HAL_F4Light/RCInput.cpp @@ -58,9 +58,6 @@ uint8_t RCInput::_valid_channels IN_CCM; // = 0; uint64_t RCInput::_last_read IN_CCM; // = 0; -uint16_t RCInput::_override[F4Light_RC_INPUT_NUM_CHANNELS] IN_CCM; -bool RCInput::_override_valid; - bool RCInput::is_PPM IN_CCM; uint8_t RCInput::_last_read_from IN_CCM; @@ -88,8 +85,6 @@ RCInput::RCInput() void RCInput::init() { caddr_t ptr; - memset((void *)&_override[0], 0, sizeof(_override)); - /* OPLINK AIR port pinout 1 2 3 4 5 6 7 PD2 PA15 @@ -104,8 +99,6 @@ for RFM int cs _last_read_from=0; max_num_pulses=0; - clear_overrides(); - pwmInit(is_PPM); // PPM sum mode uint8_t pp=0; @@ -150,8 +143,6 @@ void RCInput::late_init(uint8_t b) { // we can have 4 individual sources of data - internal DSM from UART5, SBUS from UART1 and 2 PPM parsers bool RCInput::new_input() { - if(_override_valid) return true; - uint8_t inp=hal_param_helper->_rc_input; if(inp && inp < num_parsers+1){ inp-=1; @@ -258,10 +249,6 @@ uint16_t RCInput::read(uint8_t ch) } } - /* Check for override */ - uint16_t over = _override[ch]; - if(over) return over; - if( ch == 4) { last_4 = data; } @@ -314,27 +301,6 @@ uint8_t RCInput::read(uint16_t* periods, uint8_t len) return _valid_channels; } - -bool RCInput::set_override(uint8_t channel, int16_t override) -{ - if (override < 0) return false; /* -1: no change. */ - if (channel < F4Light_RC_INPUT_NUM_CHANNELS) { - _override[channel] = override; - if (override != 0) { - _override_valid = true; - return true; - } - } - return false; -} - -void RCInput::clear_overrides() -{ - for (int i = 0; i < F4Light_RC_INPUT_NUM_CHANNELS; i++) { - set_override(i, 0); - } -} - bool RCInput::rc_bind(int dsmMode){ #ifdef BOARD_SPEKTRUM_RX_PIN return parsers[2]->bind(dsmMode); // only DSM diff --git a/libraries/AP_HAL_F4Light/RCInput.h b/libraries/AP_HAL_F4Light/RCInput.h index cd40ea44d8..9fa7118cd8 100644 --- a/libraries/AP_HAL_F4Light/RCInput.h +++ b/libraries/AP_HAL_F4Light/RCInput.h @@ -43,9 +43,6 @@ public: bool new_input() override; uint8_t num_channels() override; - bool set_override(uint8_t channel, int16_t override) override; - void clear_overrides() override; - bool rc_bind(int dsmMode) override; static uint16_t max_num_pulses; // for statistics @@ -66,10 +63,6 @@ private: static uint16_t last_4; - /* override state */ - static uint16_t _override[F4Light_RC_INPUT_NUM_CHANNELS]; - static bool _override_valid; - static bool rc_failsafe_enabled; static bool fs_flag, aibao_fs_flag;