mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: ensure RCIN sigbuf has even number of words
ObjectBuffer rounds up by 1, leaving an odd number of words, which caused DSM RC input corruption
This commit is contained in:
parent
6c128fcaf2
commit
a69f66eadd
|
@ -124,8 +124,8 @@ void RCInput::_timer_tick(void)
|
|||
#if HAL_USE_ICU == TRUE
|
||||
const uint32_t *p;
|
||||
uint32_t n;
|
||||
while ((p = sig_reader.sigbuf.readptr(n)) != nullptr) {
|
||||
rcin_prot.process_pulse_list(p, n, sig_reader.need_swap);
|
||||
while ((p = (const uint32_t *)sig_reader.sigbuf.readptr(n)) != nullptr) {
|
||||
rcin_prot.process_pulse_list(p, n*2, sig_reader.need_swap);
|
||||
sig_reader.sigbuf.advance(n);
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -102,29 +102,10 @@ void SoftSigReader::_irq_handler(void* self, uint32_t flags)
|
|||
dmaStreamSetTransactionSize(sig_reader->dma, SOFTSIG_BOUNCE_BUF_SIZE);
|
||||
dmaStreamSetMode(sig_reader->dma, sig_reader->dmamode);
|
||||
dmaStreamEnable(sig_reader->dma);
|
||||
sig_reader->sigbuf.push(sig_reader->signal2, SOFTSIG_BOUNCE_BUF_SIZE);
|
||||
sig_reader->sigbuf.push((const pulse_t *)sig_reader->signal2, SOFTSIG_BOUNCE_BUF_SIZE/2);
|
||||
}
|
||||
|
||||
|
||||
bool SoftSigReader::read(uint32_t &widths0, uint32_t &widths1)
|
||||
{
|
||||
if (sigbuf.pop(widths0) && sigbuf.pop(widths1)) {
|
||||
//the data is period and width, order depending on which
|
||||
//channel is used and width type (0 or 1) depends on mode
|
||||
//being set to HIGH or LOW. We need to swap the words when on
|
||||
//channel 1
|
||||
if (need_swap) {
|
||||
uint32_t tmp = widths1;
|
||||
widths1 = widths0;
|
||||
widths0 = tmp;
|
||||
}
|
||||
widths1 -= widths0;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif // HAL_USE_ICU
|
||||
|
||||
#endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
#define INPUT_CAPTURE_FREQUENCY 1000000 //capture unit in microseconds
|
||||
|
||||
#ifndef SOFTSIG_MAX_SIGNAL_TRANSITIONS
|
||||
#define SOFTSIG_MAX_SIGNAL_TRANSITIONS 256
|
||||
#define SOFTSIG_MAX_SIGNAL_TRANSITIONS 128
|
||||
#endif
|
||||
|
||||
// we use a small bounce buffer size to minimise time in the DMA
|
||||
|
@ -36,7 +36,6 @@ class ChibiOS::SoftSigReader {
|
|||
friend class ChibiOS::RCInput;
|
||||
public:
|
||||
bool attach_capture_timer(ICUDriver* icu_drv, icuchannel_t chan, uint8_t dma_stream, uint32_t dma_channel);
|
||||
bool read(uint32_t &widths0, uint32_t &widths1);
|
||||
|
||||
private:
|
||||
uint32_t *signal;
|
||||
|
@ -49,7 +48,11 @@ private:
|
|||
uint32_t dmamode;
|
||||
ICUConfig icucfg;
|
||||
ICUDriver* _icu_drv = nullptr;
|
||||
ObjectBuffer<uint32_t> sigbuf{SOFTSIG_MAX_SIGNAL_TRANSITIONS};
|
||||
typedef struct PACKED {
|
||||
uint32_t w0;
|
||||
uint32_t w1;
|
||||
} pulse_t;
|
||||
ObjectBuffer<pulse_t> sigbuf{SOFTSIG_MAX_SIGNAL_TRANSITIONS};
|
||||
bool need_swap;
|
||||
};
|
||||
|
||||
|
|
|
@ -93,20 +93,20 @@ void SoftSigReaderInt::init(EICUDriver* icu_drv, eicuchannel_t chan)
|
|||
void SoftSigReaderInt::_irq_handler(EICUDriver *eicup, eicuchannel_t aux_channel)
|
||||
{
|
||||
eicuchannel_t channel = get_pair_channel(aux_channel);
|
||||
uint16_t value1 = eicup->tim->CCR[channel];
|
||||
uint16_t value2 = eicup->tim->CCR[aux_channel];
|
||||
pulse_t pulse;
|
||||
pulse.w0 = eicup->tim->CCR[channel];
|
||||
pulse.w1 = eicup->tim->CCR[aux_channel];
|
||||
|
||||
_instance->sigbuf.push(value1);
|
||||
_instance->sigbuf.push(value2);
|
||||
_instance->sigbuf.push(pulse);
|
||||
|
||||
//check for missed interrupt
|
||||
uint32_t mask = (STM32_TIM_SR_CC1OF << channel) | (STM32_TIM_SR_CC1OF << aux_channel);
|
||||
if ((eicup->tim->SR & mask) != 0) {
|
||||
//we have missed some pulses
|
||||
//try to reset RCProtocol parser by returning invalid value (i.e. 0 width pulse)
|
||||
_instance->sigbuf.push(value2);
|
||||
//second 0 width pulse to keep polarity right
|
||||
_instance->sigbuf.push(value2);
|
||||
pulse.w0 = 0;
|
||||
pulse.w1 = 0;
|
||||
_instance->sigbuf.push(pulse);
|
||||
//reset overcapture mask
|
||||
eicup->tim->SR &= ~mask;
|
||||
}
|
||||
|
@ -114,12 +114,12 @@ void SoftSigReaderInt::_irq_handler(EICUDriver *eicup, eicuchannel_t aux_channel
|
|||
|
||||
bool SoftSigReaderInt::read(uint32_t &widths0, uint32_t &widths1)
|
||||
{
|
||||
uint16_t p0, p1;
|
||||
if (sigbuf.available() >= 2) {
|
||||
if (sigbuf.pop(p0) && sigbuf.pop(p1)) {
|
||||
widths0 = uint16_t(p0 - last_value);
|
||||
widths1 = uint16_t(p1 - p0);
|
||||
last_value = p1;
|
||||
pulse_t pulse;
|
||||
if (sigbuf.pop(pulse)) {
|
||||
widths0 = uint16_t(pulse.w0 - last_value);
|
||||
widths1 = uint16_t(pulse.w1 - pulse.w0);
|
||||
last_value = pulse.w1;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
|
||||
#define INPUT_CAPTURE_FREQUENCY 1000000 //capture unit in microseconds
|
||||
#ifndef SOFTSIG_MAX_SIGNAL_TRANSITIONS
|
||||
#define SOFTSIG_MAX_SIGNAL_TRANSITIONS 256
|
||||
#define SOFTSIG_MAX_SIGNAL_TRANSITIONS 128
|
||||
#endif
|
||||
|
||||
|
||||
|
@ -49,8 +49,11 @@ private:
|
|||
static void _irq_handler(EICUDriver *eicup, eicuchannel_t channel);
|
||||
|
||||
static eicuchannel_t get_pair_channel(eicuchannel_t channel);
|
||||
|
||||
ObjectBuffer<uint16_t> sigbuf{SOFTSIG_MAX_SIGNAL_TRANSITIONS};
|
||||
typedef struct PACKED {
|
||||
uint16_t w0;
|
||||
uint16_t w1;
|
||||
} pulse_t;
|
||||
ObjectBuffer<pulse_t> sigbuf{SOFTSIG_MAX_SIGNAL_TRANSITIONS};
|
||||
EICUConfig icucfg;
|
||||
EICUChannelConfig channel_config;
|
||||
EICUChannelConfig aux_channel_config;
|
||||
|
|
|
@ -133,7 +133,7 @@ define NO_DATAFLASH TRUE
|
|||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
# reduce memory usage in RCInput
|
||||
define SOFTSIG_MAX_SIGNAL_TRANSITIONS 256
|
||||
define SOFTSIG_MAX_SIGNAL_TRANSITIONS 128
|
||||
|
||||
define IOMCU_FW TRUE
|
||||
define NO_FASTBOOT
|
||||
|
|
Loading…
Reference in New Issue