This reverts commit 5de6c690d8.
That commit broke the build for the affected board as the chibios
headers rely on the name of the file matching a ifdef
this fixes an issue found by Andy Piper where the H743 bootloader gets
a hard fault in the DCache enable code when SRAM1 is primary memory.
This is the simplest fix I could think of, and avoids the problem by
making DTCM the first segment in the bootloader.
Note that we can't use DTCM as first segment for main firmware since
we went to double precision EKF as the static variables don't fit
this changes the heuristics for UART TX DMA allocation to greatly
reduce the chances of DMA contention causing long delays on other
devices
This fixes issues with FETTec driver output and gimbal status messages
as reported by Amilcar and OlliW. The problem is particularly bad when
no GPS is connected to GPS1 on fmuv3 and derived boards (such as
CubeBlack)
key changes:
- remember the contention_counter across begin() calls, as the GPS
calls begin with new baudrates regularly
- added a is_shared() API to Shared_DMA, allowing the UART driver to
avoid TX DMA on shared streams when at low baudrates.
refactor rcout into separate thread and process all dshot requests there
move uart DMA completion to event model
process dshot locks in strick reverse order when unlocking
convert Shared_DMA to use mutexes
move UART transmit to a thread-per-uart
do blocking UART DMA transactions
do blocking dshot DMA transactions
trim stack sizes
cancel dma transactions on dshot when timeout occurs
support contention stats on blocking locking
move thread supression into chibios_hwdef.py
invalidate DMA bounce buffer correctly
separate UART initialisation into two halves
cleanup UART transaction timeouts
add @SYS/uarts.txt
move half-duplex handling to TX thread
correct thread statistics after use of ExpandingString
set unbuffered TX thread priority owner + 1
correctly unlock serial_led_send()
don't share IMU RX on KakuteF7Mini
observe dshot pulse time more accurately.
set TRBUFF bit for UART DMA transfers
deal with UART DMA timeouts correctly
don't deadlock on reverse ordered DMA locks
change PORT_INT_REQUIRED_STACK to 128
When hw flow control is enabled check the CTS pin before we grab the
DMA channel to prevent a long timeout trying to send to a blocked port
from holding a DMA channel against another device
this fixes issue #16587
Adjust SRAM1+SRAM2 to 256k as describe in the H743 reference manual
Provide access to mem_info() information
Co-authored-by: Andrew Tridgell <andrew@tridgell.net>