Skip to content

Commit

Permalink
[stm32] Switch FDCAN from Queue Mode to FIFO Mode
Browse files Browse the repository at this point in the history
Queue Mode will send CAN frames in priority order according to their
arbitration ID. This is inconsistent with modm's software-managed queue
which is a strict FIFO. To make the behavior of the driver consistent
with an end-to-end FIFO order, we disable Queue Mode.

Note that the fdcan unit test was implicitly assuming FIFO order. This
change also fixes that test for larger HW TX buffer sizes.
  • Loading branch information
WasabiFan committed Sep 16, 2024
1 parent 7f2e551 commit 09839c6
Showing 1 changed file with 0 additions and 3 deletions.
3 changes: 0 additions & 3 deletions src/modm/platform/can/stm32-fdcan/can.cpp.in
Original file line number Diff line number Diff line change
Expand Up @@ -256,9 +256,6 @@ modm::platform::Fdcan{{ id }}::initializeWithPrescaler(
{{ reg }}->RXGFC |= (MessageRam::Config.filterCountStandard << FDCAN_RXGFC_LSS_Pos) | (MessageRam::Config.filterCountExtended << FDCAN_RXGFC_LSE_Pos);
%%endif

// Tx buffer: queue mode
{{ reg }}->TXBC |= FDCAN_TXBC_TFQM;

// Enable bit rate switching and CANFD frame format
if(fdDataTimings) {
{{ reg }}->CCCR |= FDCAN_CCCR_BRSE | FDCAN_CCCR_FDOE;
Expand Down

0 comments on commit 09839c6

Please sign in to comment.