HAL_ChibiOS: use more efficient push mechanism in IRQ

and don't use push_force() as it is not safe to do reads from within
the producer
This commit is contained in:
Andrew Tridgell 2018-01-18 09:39:32 +11:00
parent d030f2888b
commit 33c7cba9af

View File

@ -76,10 +76,7 @@ bool SoftSigReader::attach_capture_timer(ICUDriver* icu_drv, icuchannel_t chan,
void SoftSigReader::_irq_handler(void* self, uint32_t flags)
{
SoftSigReader* sig_reader = (SoftSigReader*)self;
for (uint16_t i = 0; i < sig_reader->_bounce_buf_size; i++) {
sig_reader->sigbuf.push_force(sig_reader->signal[i]);
sig_reader->signal[i] = 0;
}
sig_reader->sigbuf.push(sig_reader->signal, sig_reader->_bounce_buf_size);
//restart the DMA transfers
dmaStreamSetMemory0(sig_reader->dma, sig_reader->signal);
dmaStreamSetTransactionSize(sig_reader->dma, sig_reader->_bounce_buf_size);