* Support for armv7-m_dcache control via parameter
The FORCE_F7_DCACHE parameter can be set to
0 - (default) if Eratta exits turn dcache off else leave it on
1 - Force it off
2 - Force it on
At boot the system will disable the d-cache if the silicon
has the 1259864 Data corruption in a sequence of Write-Through
stores and loads eratta.
Post nsh script execution the FORCE_F7_DCACHE paramater
will be used to set the d-cache to the state indicated
above.
- see 1259864 Data corruption in a sequence of Write-Through stores and loads
- if we can be certain this sequence won't occur in PX4 then the d-cache will be re-enabled
This insures the common exception handler will not be
re-entered. The handler does not support nested interrupts
and the interrupt stack pointer and context will be overwritten
resulting in hard to debug hardfaults.
If all the priorities are equal the NVIC prevents the
preemption. The startup code defaults all the priorities
to the same value 128.
This change safeguards in 2 ways 1) By disabling
CONFIG_ ARCH_IRQPRIO: up_prioritize_irq cannot be called.
This will insure that all HW interrupts are at the same
priority.
2) By disabling CONFIG_ARCH_HIPRI_INTERRUP, the common
exception will disable any interrupts during interrupt
processing.
* Backport:stm32f7: stm32_allocateheap: allow use DTCM memory for heap
Back port of upstrem contrib by Jussi Kivilinna <jussi.kivilinna@haltian.com>
stm32f7: stm32_allocateheap: allow use DTCM memory for heap
STM32F7 has up to 128KiB of DTCM memory that is currently left unused.
This patch adds DTCM to main heap if CONFIG_STM32F7_DTCMEXCLUDE is not enabled.
* px4fmu-v5_default:Enable inclusion of the DTCM in the heap
CONFIG_MM_REGIONS=3 adds the DTCM region to the heap.
This saves almost 2kb of RAM when using the mavlink shell. 70 matches the
size of the mavlink message. Since the pipe is blocking, a process writing
a lot of data will just wait, data will not be dropped.
The mavlink shell is the only process creating a pipe.