HAL_ChibiOS: removed RC inversion logic

not needed any more
This commit is contained in:
Andrew Tridgell 2018-01-19 08:40:28 +11:00
parent d6b9ab7756
commit ab748034a2
4 changed files with 0 additions and 28 deletions

View File

@ -37,8 +37,6 @@ void RCInput::init()
#endif
chMtxObjectInit(&rcin_mutex);
_init = true;
//timeout starts from the initialisation
_rcin_detect_timeout = AP_HAL::micros();
}
bool RCInput::new_input()
@ -186,11 +184,6 @@ void RCInput::_timer_tick(void)
}
chMtxUnlock(&rcin_mutex);
}
//we reset if nothing detected for SIG_DETECT_TIMEOUT_US
if (AP_HAL::micros() - _rcin_detect_timeout > SIG_DETECT_TIMEOUT_US) {
_rcin_detect_timeout = AP_HAL::micros();
sig_reader.invert();
}
#endif
#ifdef HAL_RCINPUT_WITH_AP_RADIO

View File

@ -62,7 +62,6 @@ private:
mutex_t rcin_mutex;
int16_t _rssi = -1;
uint32_t _rcin_timestamp_last_signal;
uint32_t _rcin_detect_timeout;
bool _init;
#ifdef HAL_RCINPUT_WITH_AP_RADIO
bool _radio_init;

View File

@ -107,24 +107,6 @@ bool SoftSigReader::read(uint32_t &widths0, uint32_t &widths1)
return true;
}
void SoftSigReader::invert()
{
if (_icu_drv == nullptr) {
return;
}
icuStopCapture(_icu_drv);
icuStop(_icu_drv);
if (icucfg.mode == ICU_INPUT_ACTIVE_LOW) {
icucfg.mode = ICU_INPUT_ACTIVE_HIGH;
} else {
icucfg.mode = ICU_INPUT_ACTIVE_LOW;
}
icuStart(_icu_drv, &icucfg);
_icu_drv->tim->DCR = STM32_TIM_DCR_DBA(0x0D) | STM32_TIM_DCR_DBL(1);
icuStartCapture(_icu_drv);
}
bool SoftSigReader::set_bounce_buf_size(uint16_t buf_size)
{

View File

@ -32,8 +32,6 @@ public:
bool read(uint32_t &widths0, uint32_t &widths1);
//This sets the size of bounce buffer size, which in turn controls the rate of interrupt from DMA
bool set_bounce_buf_size(uint16_t buf_size);
//inverts the signal input mode
void invert();
private:
uint32_t *signal;
static void _irq_handler(void* self, uint32_t flags);