From 7b9f0f3fd73741fd8bf302a53f850512a6588226 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 20 May 2020 11:47:34 +0530 Subject: [PATCH] HAL_ChibiOS: use FIFO mode instead of Queue mode in FDCAN driver --- libraries/AP_HAL_ChibiOS/CANFDIface.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/CANFDIface.cpp b/libraries/AP_HAL_ChibiOS/CANFDIface.cpp index 57d426b46d..c66dab9ee7 100644 --- a/libraries/AP_HAL_ChibiOS/CANFDIface.cpp +++ b/libraries/AP_HAL_ChibiOS/CANFDIface.cpp @@ -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; }