Open tridge opened 4 years ago
On Tue, 28 Apr 2020, Andrew Tridgell wrote:
- allow for runtime DMA stream assignment. The job of dma_resolver.py will be to get the list of possible DMA streams a peripheral can use. Then a runtime allocator will assign streams from the available set. Runtime assignment will require some tricks with cpp macros, as ChibiOS uses #defines
Are all DMA streams created equal? i.e. is this really just a set of identical resources?
Are all DMA streams created equal?
no, on F4 and F7 specific peripherals can use specific streams. On H7 peripherals are limited to a particular DMA controller, but not a specific stream within that controller
This sounds like a reasonable approach to me, although i'm not sure of the implications of changing from semaphores to mutexes... we use semaphores a lot.... is there an expectation of there being a performance benefit to mutexes ..?
The strategy we use for handling DMA channels in HAL_ChibiOS needs an overhaul. The current strategy is:
The problems with this strategy are:
To solve this I would like to make the following changes: