Reduce overhead when doing SPI transactions
-
Tested on CubeOrangePlus and CubeRedPrimary with Invensensev3 driver
-
I used debug trace to analyse timeline for read_fifo to check if we have any substantial overhead while doing SPI transactions. It turned out that calling spiStart and spiStop which in turn call dmaStreamAlloc and and dealloc to take substantial amount of CPU call almost 3-4us. Also we were calling Shared DMA mutex lock and unlock when the DMA is not shared between peripherals.
-
Following changes made SPI transactions much less CPU intensive:
-
- Do not reset SPI peripheral using spistop and spistart calls if SPI config hasn't changed.
-
- Also make changes to SPI frequencies for CubeOrangePlus and CubeRedPrimary to match on the bus where possible (minor CPU gain through this, just first part was enough as most transactions are IMU anyways).
-
- Do not call mutex lock unlock for unshared DMAs.
Results:
CubeRedPrimary:
Before: SPI1 PRI=181 sp=0x20001AA8 STACK= 792/1464 LOAD=13.4% SPI4 PRI=181 sp=0x200021C0 STACK= 872/1464 LOAD=13.4% SPI2 PRI=181 sp=0x20005380 STACK= 896/1464 LOAD=13.3%
After: SPI1 PRI=181 sp=0x20001B08 STACK= 792/1464 LOAD= 9.7% SPI4 PRI=181 sp=0x20002220 STACK= 792/1464 LOAD=11.2% SPI2 PRI=181 sp=0x200053E0 STACK= 840/1464 LOAD= 8.3%
CubeOrangePlus:
Before: SPI4 PRI=181 sp=0x3002AF58 STACK= 668/1464 LOAD=25.5% SPI1 PRI=181 sp=0x3002B668 STACK= 668/1464 LOAD=14.5%
After: SPI4 PRI=181 sp=0x3002AF78 STACK= 668/1464 LOAD=19.2% SPI1 PRI=181 sp=0x3002B688 STACK= 668/1464 LOAD= 9.5%
10% total CPU time recovered for both CubeOrangePlus and CubeRedPrimary
I did a short flight with just the SPI changes - had no issues and this gives a nice bump of about 5% CPU gain, which with my Dynamic FIFO change (https://github.com/ArduPilot/ardupilot/pull/27841) is giving me about 15% CPU gain
@bugobliterator I'd like to discuss this a bit more with you. There are risks to not restarting the SPI peripheral. If (due to eg. a voltage spike) the SPI peripheral gets into a bad state, then with a single sensor bus that state could persist forever and take down the vehicle. We switched to always re-init some time ago when we saw this sort of bad persistent state on I2C peripherals. I'd really rather fix the real problem which is that we are doing transfers at such a high rate for InvensenseV3