HAL_ChibiOS: use FIFO mode instead of Queue mode in FDCAN driver

This commit is contained in:
bugobliterator 2020-05-20 11:47:34 +05:30 committed by Andrew Tridgell
parent 9269ee50ed
commit 7b9f0f3fd7
1 changed files with 0 additions and 1 deletions

View File

@ -598,7 +598,6 @@ void CanIface::setupMessageRam()
num_elements = MIN((FDCAN_TX_FIFO_BUFFER_SIZE/FDCAN_FRAME_BUFFER_SIZE), 32U);
if (num_elements) {
can_->TXBC = (FDCANMessageRAMOffset_ << 2) | (num_elements << 24);
can_->TXBC |= 1U << 30; //Set Queue mode
MessageRam_.TxFIFOQSA = SRAMCAN_BASE + (FDCANMessageRAMOffset_ * 4U);
FDCANMessageRAMOffset_ += num_elements*FDCAN_FRAME_BUFFER_SIZE;
}