F7 optimizations (#5674)

* Revert "Revert "Rewritten F7 dshot to LL (draft)" (#5430)"

This reverts commit aa42a69d2f.

* Reworked F7 linker scripts to maximize performance of both F74x and F72x

* Some comments and changes from original F7 HAL DSHOT

* Prohibit inlining of some functions to place them in ITCM-RAM

* Fixed usartTargetConfigure implicit declaration

* Moved back to SRAM1 as main RAM

* Added SRAM2 attribute

* Fixed LL DSHOT FOR SPRF7DUAL and probably other adv TIM users

* Fixed SPRF7DUAL rev. A motor order

* Enabled CCM for data on F40x

* Fixed F7 startup assembly symbols

* Fixed KISSFCV2F7 linker script

* Added a quick way of building F7 targets only

* Got rid of the useless F7 target script

* Added NOINLINE and got rid of useless __APPLE__ define

* Added some important functions to ITCM

* Added NOINLINE macro for tests

* Copy to ITCM before passing execution into it

* Minimized cache footprint of motor output code

* Evicted low-impact functions from ITCM

* Switched MATEKF722 and SPRACINGF7DUAL to burst DSHOT

* Switched CLRACINGF7 to burst DSHOT

* Moved UART RX&TX buffers to DTCM-RAM to avoid cache incoherency

* Marked taskMainPidLoop for ITCM-RAM, disallowed inlining per-function

* Revert "Added a quick way of building F7 targets only"

This reverts commit 22945189980deaf493be54a5056a080e7edad629.
This commit is contained in:
Andrey Mironov 2018-04-19 23:37:32 +03:00 committed by Michael Keller
parent 39fec69fb0
commit bf984f39b1
34 changed files with 503 additions and 345 deletions

View File

@ -154,10 +154,14 @@ __IO uint32_t uwTick;
HAL_StatusTypeDef HAL_Init(void)
{
/* Configure Flash prefetch and Instruction cache through ART accelerator */
#if (ART_ACCLERATOR_ENABLE != 0)
#if (ART_ACCLERATOR_ENABLE != 0U)
__HAL_FLASH_ART_ENABLE();
#endif /* ART_ACCLERATOR_ENABLE */
#if (PREFETCH_ENABLE != 0U)
__HAL_FLASH_PREFETCH_BUFFER_ENABLE();
#endif /* PREFETCH_ENABLE */
/* Set Interrupt Group Priority */
HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4);

View File

@ -129,14 +129,14 @@ ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fs
DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER
ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XG_TARGETS)))
DEVICE_FLAGS += -DSTM32F745xx
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f745.ld
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f74x.ld
STARTUP_SRC = startup_stm32f745xx.s
TARGET_FLASH := 2048
TARGET_FLASH := 1024
else ifeq ($(TARGET),$(filter $(TARGET),$(F7X6XG_TARGETS)))
DEVICE_FLAGS += -DSTM32F746xx
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f746.ld
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f74x.ld
STARTUP_SRC = startup_stm32f746xx.s
TARGET_FLASH := 2048
TARGET_FLASH := 1024
else ifeq ($(TARGET),$(filter $(TARGET),$(F7X2RE_TARGETS)))
DEVICE_FLAGS += -DSTM32F722xx
ifndef LD_SCRIPT

View File

@ -28,12 +28,12 @@
#include "timer.h"
#include "drivers/pwm_output.h"
static pwmWriteFn *pwmWrite;
static pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
static pwmCompleteWriteFn *pwmCompleteWrite = NULL;
static FAST_RAM pwmWriteFn *pwmWrite;
static FAST_RAM pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
static FAST_RAM pwmCompleteWriteFn *pwmCompleteWrite = NULL;
#ifdef USE_DSHOT
loadDmaBufferFn *loadDmaBuffer;
FAST_RAM loadDmaBufferFn *loadDmaBuffer;
#endif
#ifdef USE_SERVOS
@ -48,7 +48,7 @@ static uint16_t freqBeep = 0;
static bool pwmMotorsEnabled = false;
static bool isDshot = false;
#ifdef USE_DSHOT_DMAR
bool useBurstDshot = false;
FAST_RAM bool useBurstDshot = false;
#endif
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t output)
@ -135,12 +135,12 @@ static void pwmWriteStandard(uint8_t index, float value)
}
#ifdef USE_DSHOT
static void pwmWriteDshot(uint8_t index, float value)
static FAST_CODE void pwmWriteDshot(uint8_t index, float value)
{
pwmWriteDshotInt(index, lrintf(value));
}
static uint8_t loadDmaBufferDshot(uint32_t *dmaBuffer, int stride, uint16_t packet)
static FAST_CODE uint8_t loadDmaBufferDshot(uint32_t *dmaBuffer, int stride, uint16_t packet)
{
for (int i = 0; i < 16; i++) {
dmaBuffer[i * stride] = (packet & 0x8000) ? MOTOR_BIT_1 : MOTOR_BIT_0; // MSB first
@ -405,7 +405,7 @@ void pwmWriteDshotCommand(uint8_t index, uint8_t motorCount, uint8_t command)
}
}
uint16_t prepareDshotPacket(motorDmaOutput_t *const motor, const uint16_t value)
FAST_CODE uint16_t prepareDshotPacket(motorDmaOutput_t *const motor, const uint16_t value)
{
uint16_t packet = (value << 1) | (motor->requestTelemetry ? 1 : 0);
motor->requestTelemetry = false; // reset telemetry request to make sure it's triggered only once in a row

View File

@ -110,14 +110,12 @@ typedef enum {
typedef struct {
TIM_TypeDef *timer;
#if defined(USE_DSHOT) && defined(USE_DSHOT_DMAR)
#if !defined(USE_HAL_DRIVER)
#ifdef STM32F3
DMA_Channel_TypeDef *dmaBurstRef;
#else
DMA_Stream_TypeDef *dmaBurstRef;
#endif
uint16_t dmaBurstLength;
#endif
uint32_t dmaBurstBuffer[DSHOT_DMA_BUFFER_SIZE * 4];
#endif
uint16_t timerDmaSources;
@ -138,11 +136,6 @@ typedef struct {
#else
uint8_t dmaBuffer[DSHOT_DMA_BUFFER_SIZE];
#endif
#if defined(USE_HAL_DRIVER)
TIM_HandleTypeDef TimHandle;
DMA_HandleTypeDef hdma_tim;
uint16_t timerDmaIndex;
#endif
} motorDmaOutput_t;
motorDmaOutput_t *getMotorDmaOutput(uint8_t index);

View File

@ -29,9 +29,9 @@
#include "dma.h"
#include "rcc.h"
static uint8_t dmaMotorTimerCount = 0;
static motorDmaTimer_t dmaMotorTimers[MAX_DMA_TIMERS];
static motorDmaOutput_t dmaMotors[MAX_SUPPORTED_MOTORS];
static FAST_RAM uint8_t dmaMotorTimerCount = 0;
static FAST_RAM motorDmaTimer_t dmaMotorTimers[MAX_DMA_TIMERS];
static FAST_RAM motorDmaOutput_t dmaMotors[MAX_SUPPORTED_MOTORS];
motorDmaOutput_t *getMotorDmaOutput(uint8_t index)
{
@ -49,7 +49,7 @@ uint8_t getTimerIndex(TIM_TypeDef *timer)
return dmaMotorTimerCount - 1;
}
void pwmWriteDshotInt(uint8_t index, uint16_t value)
FAST_CODE void pwmWriteDshotInt(uint8_t index, uint16_t value)
{
motorDmaOutput_t *const motor = &dmaMotors[index];
@ -58,232 +58,248 @@ void pwmWriteDshotInt(uint8_t index, uint16_t value)
}
uint16_t packet = prepareDshotPacket(motor, value);
uint8_t bufferSize;
#ifdef USE_DSHOT_DMAR
if (useBurstDshot) {
bufferSize = loadDmaBuffer(&motor->timer->dmaBurstBuffer[timerLookupChannelIndex(motor->timerHardware->channel)], 4, packet);
if (HAL_DMA_STATE_READY == motor->TimHandle.hdma[motor->timerDmaIndex]->State) {
HAL_DMA_Start_IT(motor->TimHandle.hdma[motor->timerDmaIndex], (uint32_t)motor->timer->dmaBurstBuffer, (uint32_t)&motor->TimHandle.Instance->DMAR, bufferSize * 4);
}
motor->timer->dmaBurstLength = bufferSize * 4;
} else
#endif
{
bufferSize = loadDmaBuffer(motor->dmaBuffer, 1, packet);
if (DMA_SetCurrDataCounter(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, bufferSize) != HAL_OK) {
/* DMA set error */
return;
}
motor->timer->timerDmaSources |= motor->timerDmaSource;
// @todo LL_DMA_SetDataLength
MODIFY_REG(motor->timerHardware->dmaRef->NDTR, DMA_SxNDT, bufferSize);
// @todo LL_DMA_EnableStream
SET_BIT(motor->timerHardware->dmaRef->CR, DMA_SxCR_EN);
}
}
void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
FAST_CODE void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
{
UNUSED(motorCount);
for (int i = 0; i < dmaMotorTimerCount; i++) {
#ifdef USE_DSHOT_DMAR
if (useBurstDshot) {
// @todo LL_DMA_SetDataLength
MODIFY_REG(dmaMotorTimers[i].dmaBurstRef->NDTR, DMA_SxNDT, dmaMotorTimers[i].dmaBurstLength);
// @todo LL_DMA_EnableStream
SET_BIT(dmaMotorTimers[i].dmaBurstRef->CR, DMA_SxCR_EN);
/* configure the DMA Burst Mode */
LL_TIM_ConfigDMABurst(dmaMotorTimers[i].timer, LL_TIM_DMABURST_BASEADDR_CCR1, LL_TIM_DMABURST_LENGTH_4TRANSFERS);
/* Enable the TIM DMA Request */
LL_TIM_EnableDMAReq_UPDATE(dmaMotorTimers[i].timer);
/* Reset timer counter */
LL_TIM_SetCounter(dmaMotorTimers[i].timer, 0);
if(IS_TIM_ADVANCED_INSTANCE(dmaMotorTimers[i].timer) != RESET) {
/* Enable the main output */
LL_TIM_EnableAllOutputs(dmaMotorTimers[i].timer);
}
/* Enable the counter */
LL_TIM_EnableCounter(dmaMotorTimers[i].timer);
} else
#endif
{
/* Reset timer counter */
LL_TIM_SetCounter(dmaMotorTimers[i].timer, 0);
/* Enable channel DMA requests */
dmaMotorTimers[i].timer->DIER |= dmaMotorTimers[i].timerDmaSources;
SET_BIT(dmaMotorTimers[i].timer->DIER, dmaMotorTimers[i].timerDmaSources);
dmaMotorTimers[i].timerDmaSources = 0;
}
}
}
static void motor_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
{
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam];
HAL_DMA_IRQHandler(motor->TimHandle.hdma[motor->timerDmaIndex]);
#ifdef USE_DSHOT_DMAR
if (useBurstDshot) {
LL_TIM_DisableCounter(motor->timerHardware->tim);
// @todo LL_DMA_DisableStream
CLEAR_BIT(motor->timerHardware->dmaTimUPRef->CR, DMA_SxCR_EN);
LL_TIM_DisableDMAReq_UPDATE(motor->timerHardware->tim);
} else
#endif
{
__HAL_DMA_DISABLE(&motor->hdma_tim);
TIM_DMACmd(&motor->TimHandle, motor->timerHardware->channel, DISABLE);
// @todo LL_DMA_DisableStream
CLEAR_BIT(motor->timerHardware->dmaRef->CR, DMA_SxCR_EN);
CLEAR_BIT(motor->timerHardware->tim->DIER, motor->timerDmaSource);
}
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
}
}
void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output)
{
DMA_Stream_TypeDef *dmaRef;
#ifdef USE_DSHOT_DMAR
if (useBurstDshot && timerHardware->dmaTimUPRef == NULL) {
return;
if (useBurstDshot) {
dmaRef = timerHardware->dmaTimUPRef;
} else
#endif
if (timerHardware->dmaRef == NULL) {
{
dmaRef = timerHardware->dmaRef;
}
if (dmaRef == NULL) {
return;
}
LL_TIM_OC_InitTypeDef oc_init;
LL_DMA_InitTypeDef dma_init;
motorDmaOutput_t * const motor = &dmaMotors[motorIndex];
motor->timerHardware = timerHardware;
TIM_TypeDef *timer = timerHardware->tim;
const IO_t motorIO = IOGetByTag(timerHardware->tag);
const uint8_t timerIndex = getTimerIndex(timer);
const bool configureTimer = (timerIndex == dmaMotorTimerCount - 1);
// @note original DSHOT for F7 has pulldown instead of pullup
IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLDOWN), timerHardware->alternateFunction);
__DMA1_CLK_ENABLE();
if (configureTimer) {
LL_TIM_InitTypeDef init;
LL_TIM_StructInit(&init);
RCC_ClockCmd(timerRCC(timer), ENABLE);
LL_TIM_DisableCounter(timer);
motor->TimHandle.Instance = timerHardware->tim;
motor->TimHandle.Init.Prescaler = lrintf((float) timerClock(timer) / getDshotHz(pwmProtocolType) + 0.01f) - 1;
motor->TimHandle.Init.Period = pwmProtocolType == PWM_TYPE_PROSHOT1000 ? MOTOR_NIBBLE_LENGTH_PROSHOT : MOTOR_BITLENGTH;
motor->TimHandle.Init.RepetitionCounter = 0;
motor->TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
motor->TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
motor->TimHandle.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_PWM_Init(&motor->TimHandle) != HAL_OK) {
/* Initialization Error */
return;
init.Prescaler = (uint16_t)(lrintf((float) timerClock(timer) / getDshotHz(pwmProtocolType) + 0.01f) - 1);
init.Autoreload = pwmProtocolType == PWM_TYPE_PROSHOT1000 ? MOTOR_NIBBLE_LENGTH_PROSHOT : MOTOR_BITLENGTH;
init.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1;
init.RepetitionCounter = 0;
init.CounterMode = LL_TIM_COUNTERMODE_UP;
LL_TIM_Init(timer, &init);
}
// Note that a timer and an associated DMA are initialized more than once.
// To fix it, getTimerIndex must be expanded to return if a new timer has been requested.
// However, since the initialization is idempotent, it is left as is in a favor of flash space (for now).
LL_TIM_OC_StructInit(&oc_init);
oc_init.OCMode = LL_TIM_OCMODE_PWM1;
if (output & TIMER_OUTPUT_N_CHANNEL) {
oc_init.OCNState = LL_TIM_OCSTATE_ENABLE;
oc_init.OCNIdleState = LL_TIM_OCIDLESTATE_LOW;
oc_init.OCNPolarity = (output & TIMER_OUTPUT_INVERTED) ? LL_TIM_OCPOLARITY_LOW : LL_TIM_OCPOLARITY_HIGH;
} else {
oc_init.OCState = LL_TIM_OCSTATE_ENABLE;
oc_init.OCIdleState = LL_TIM_OCIDLESTATE_HIGH;
oc_init.OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? LL_TIM_OCPOLARITY_LOW : LL_TIM_OCPOLARITY_HIGH;
}
oc_init.CompareValue = 0;
motor->timer = &dmaMotorTimers[getTimerIndex(timer)];
uint32_t channel;
switch (timerHardware->channel) {
case TIM_CHANNEL_1: channel = LL_TIM_CHANNEL_CH1; break;
case TIM_CHANNEL_2: channel = LL_TIM_CHANNEL_CH2; break;
case TIM_CHANNEL_3: channel = LL_TIM_CHANNEL_CH3; break;
case TIM_CHANNEL_4: channel = LL_TIM_CHANNEL_CH4; break;
}
LL_TIM_OC_Init(timer, channel, &oc_init);
LL_TIM_OC_EnablePreload(timer, channel);
// @note original DSHOT for F7
LL_TIM_OC_DisableFast(timer, channel);
/* Set the common dma handle parameters to be configured */
motor->hdma_tim.Init.Direction = DMA_MEMORY_TO_PERIPH;
motor->hdma_tim.Init.PeriphInc = DMA_PINC_DISABLE;
motor->hdma_tim.Init.MemInc = DMA_MINC_ENABLE;
motor->hdma_tim.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD;
motor->hdma_tim.Init.MemDataAlignment = DMA_MDATAALIGN_WORD;
motor->hdma_tim.Init.Mode = DMA_NORMAL;
motor->hdma_tim.Init.Priority = DMA_PRIORITY_HIGH;
motor->hdma_tim.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL;
motor->hdma_tim.Init.MemBurst = DMA_MBURST_SINGLE;
motor->hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE;
if (output & TIMER_OUTPUT_N_CHANNEL) {
// @todo quick hack to get TIM_CCER_CCxNE from TIM_CCER_CCxE
LL_TIM_CC_EnableChannel(timer, 4 * channel);
} else {
LL_TIM_CC_EnableChannel(timer, channel);
}
if (configureTimer) {
LL_TIM_EnableAllOutputs(timer);
LL_TIM_EnableARRPreload(timer);
// @note original DSHOT for F7
LL_TIM_EnableCounter(timer);
}
motor->timer = &dmaMotorTimers[timerIndex];
#ifdef USE_DSHOT_DMAR
if (useBurstDshot) {
motor->timerDmaIndex = TIM_DMA_ID_UPDATE;
/* Set the DMAR specific dma handle parameters to be configured */
motor->hdma_tim.Init.Channel = timerHardware->dmaTimUPChannel;
motor->hdma_tim.Init.FIFOMode = DMA_FIFOMODE_ENABLE;
motor->timer->dmaBurstRef = dmaRef;
/* Set hdma_tim instance */
motor->hdma_tim.Instance = timerHardware->dmaTimUPRef;
if (!configureTimer) {
motor->configured = true;
return;
}
} else
#endif
{
motor->timerDmaSource = timerDmaSource(timerHardware->channel);
motor->timer->timerDmaSources &= ~motor->timerDmaSource;
}
/* Link hdma_tim to hdma[x] (channelx) */
__HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaIndex], motor->hdma_tim);
DMA_TypeDef *dma;
uint32_t stream;
if (dmaRef == DMA1_Stream0) { dma = DMA1; stream = LL_DMA_STREAM_0; }
else if (dmaRef == DMA1_Stream1) { dma = DMA1; stream = LL_DMA_STREAM_1; }
else if (dmaRef == DMA1_Stream2) { dma = DMA1; stream = LL_DMA_STREAM_2; }
else if (dmaRef == DMA1_Stream3) { dma = DMA1; stream = LL_DMA_STREAM_3; }
else if (dmaRef == DMA1_Stream4) { dma = DMA1; stream = LL_DMA_STREAM_4; }
else if (dmaRef == DMA1_Stream5) { dma = DMA1; stream = LL_DMA_STREAM_5; }
else if (dmaRef == DMA1_Stream6) { dma = DMA1; stream = LL_DMA_STREAM_6; }
else if (dmaRef == DMA1_Stream7) { dma = DMA1; stream = LL_DMA_STREAM_7; }
else if (dmaRef == DMA2_Stream0) { dma = DMA2; stream = LL_DMA_STREAM_0; }
else if (dmaRef == DMA2_Stream1) { dma = DMA2; stream = LL_DMA_STREAM_1; }
else if (dmaRef == DMA2_Stream2) { dma = DMA2; stream = LL_DMA_STREAM_2; }
else if (dmaRef == DMA2_Stream3) { dma = DMA2; stream = LL_DMA_STREAM_3; }
else if (dmaRef == DMA2_Stream4) { dma = DMA2; stream = LL_DMA_STREAM_4; }
else if (dmaRef == DMA2_Stream5) { dma = DMA2; stream = LL_DMA_STREAM_5; }
else if (dmaRef == DMA2_Stream6) { dma = DMA2; stream = LL_DMA_STREAM_6; }
else if (dmaRef == DMA2_Stream7) { dma = DMA2; stream = LL_DMA_STREAM_7; }
LL_DMA_DisableStream(dma, stream);
//CLEAR_BIT(dmaRef->CR, DMA_SxCR_EN);
LL_DMA_DeInit(dma, stream);
LL_DMA_StructInit(&dma_init);
#ifdef USE_DSHOT_DMAR
if (useBurstDshot) {
dmaInit(timerHardware->dmaTimUPIrqHandler, OWNER_TIMUP, timerGetTIMNumber(timerHardware->tim));
dmaSetHandler(timerHardware->dmaTimUPIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
dma_init.Channel = timerHardware->dmaTimUPChannel;
dma_init.MemoryOrM2MDstAddress = (uint32_t)motor->timer->dmaBurstBuffer;
dma_init.Direction = LL_DMA_DIRECTION_MEMORY_TO_PERIPH;
dma_init.FIFOMode = LL_DMA_FIFOMODE_ENABLE;
dma_init.FIFOThreshold = LL_DMA_FIFOTHRESHOLD_FULL;
dma_init.MemBurst = LL_DMA_MBURST_SINGLE;
dma_init.PeriphBurst = LL_DMA_PBURST_SINGLE;
dma_init.PeriphOrM2MSrcAddress = (uint32_t)&timerHardware->tim->DMAR;
dma_init.NbData = (pwmProtocolType == PWM_TYPE_PROSHOT1000) ? PROSHOT_DMA_BUFFER_SIZE : DSHOT_DMA_BUFFER_SIZE; // XXX
dma_init.PeriphOrM2MSrcIncMode = LL_DMA_PERIPH_NOINCREMENT;
dma_init.MemoryOrM2MDstIncMode = LL_DMA_MEMORY_INCREMENT;
dma_init.PeriphOrM2MSrcDataSize = LL_DMA_PDATAALIGN_WORD;
dma_init.MemoryOrM2MDstDataSize = LL_DMA_MDATAALIGN_WORD;
dma_init.Mode = LL_DMA_MODE_NORMAL;
dma_init.Priority = LL_DMA_PRIORITY_HIGH;
} else
#endif
{
motor->timerDmaIndex = timerDmaIndex(timerHardware->channel);
motor->timer->timerDmaSources |= timerDmaSource(timerHardware->channel);
/* Set the non-DMAR specific dma handle parameters to be configured */
motor->hdma_tim.Init.Channel = timerHardware->dmaChannel;
motor->hdma_tim.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
/* Set hdma_tim instance */
motor->hdma_tim.Instance = timerHardware->dmaRef;
/* Link hdma_tim to hdma[x] (channelx) */
__HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaIndex], motor->hdma_tim);
dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
dma_init.Channel = timerHardware->dmaChannel;
dma_init.MemoryOrM2MDstAddress = (uint32_t)motor->dmaBuffer;
dma_init.Direction = LL_DMA_DIRECTION_MEMORY_TO_PERIPH;
// @note original DSHOT for F7 disabled FIFO for non-burst
dma_init.FIFOMode = LL_DMA_FIFOMODE_ENABLE;
dma_init.FIFOThreshold = LL_DMA_FIFOTHRESHOLD_1_4;
dma_init.MemBurst = LL_DMA_MBURST_SINGLE;
dma_init.PeriphBurst = LL_DMA_PBURST_SINGLE;
dma_init.PeriphOrM2MSrcAddress = (uint32_t)timerChCCR(timerHardware);
dma_init.NbData = pwmProtocolType == PWM_TYPE_PROSHOT1000 ? PROSHOT_DMA_BUFFER_SIZE : DSHOT_DMA_BUFFER_SIZE;
dma_init.PeriphOrM2MSrcIncMode = LL_DMA_PERIPH_NOINCREMENT;
dma_init.MemoryOrM2MDstIncMode = LL_DMA_MEMORY_INCREMENT;
dma_init.PeriphOrM2MSrcDataSize = LL_DMA_PDATAALIGN_WORD;
dma_init.MemoryOrM2MDstDataSize = LL_DMA_MDATAALIGN_WORD;
dma_init.Mode = LL_DMA_MODE_NORMAL;
dma_init.Priority = LL_DMA_PRIORITY_HIGH;
}
/* Initialize TIMx DMA handle */
if (HAL_DMA_Init(motor->TimHandle.hdma[motor->timerDmaIndex]) != HAL_OK) {
/* Initialization Error */
return;
}
TIM_OC_InitTypeDef TIM_OCInitStructure;
/* PWM1 Mode configuration: Channel1 */
TIM_OCInitStructure.OCMode = TIM_OCMODE_PWM1;
TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_SET;
TIM_OCInitStructure.OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCPOLARITY_LOW : TIM_OCPOLARITY_HIGH;
TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_SET;
TIM_OCInitStructure.OCNPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPOLARITY_LOW : TIM_OCNPOLARITY_HIGH;
TIM_OCInitStructure.OCFastMode = TIM_OCFAST_DISABLE;
TIM_OCInitStructure.Pulse = 0;
if (HAL_TIM_PWM_ConfigChannel(&motor->TimHandle, &TIM_OCInitStructure, motor->timerHardware->channel) != HAL_OK) {
/* Configuration Error */
return;
}
#ifdef USE_DSHOT_DMAR
if (useBurstDshot) {
/* Enable the Output compare channel */
uint32_t channels = 0;
if(output & TIMER_OUTPUT_N_CHANNEL) {
switch(motor->timerHardware->channel) {
case TIM_CHANNEL_1:
channels = LL_TIM_CHANNEL_CH1N;
break;
case TIM_CHANNEL_2:
channels = LL_TIM_CHANNEL_CH2N;
break;
case TIM_CHANNEL_3:
channels = LL_TIM_CHANNEL_CH3N;
break;
}
} else {
switch(motor->timerHardware->channel) {
case TIM_CHANNEL_1:
channels = LL_TIM_CHANNEL_CH1;
break;
case TIM_CHANNEL_2:
channels = LL_TIM_CHANNEL_CH2;
break;
case TIM_CHANNEL_3:
channels = LL_TIM_CHANNEL_CH3;
break;
case TIM_CHANNEL_4:
channels = LL_TIM_CHANNEL_CH4;
break;
}
}
LL_TIM_CC_EnableChannel(motor->timerHardware->tim, channels);
} else
#endif
{
if (output & TIMER_OUTPUT_N_CHANNEL) {
if (HAL_TIMEx_PWMN_Start(&motor->TimHandle, motor->timerHardware->channel) != HAL_OK) {
/* Starting PWM generation Error */
return;
}
} else {
if (HAL_TIM_PWM_Start(&motor->TimHandle, motor->timerHardware->channel) != HAL_OK) {
/* Starting PWM generation Error */
return;
}
}
}
// XXX Consolidate common settings in the next refactor
LL_DMA_Init(dma, stream, &dma_init);
LL_DMA_EnableIT_TC(dma, stream);
motor->configured = true;
}

View File

@ -95,6 +95,7 @@ void uartReconfigure(uartPort_t *uartPort)
usartConfigurePinInversion(uartPort);
#ifdef TARGET_USART_CONFIG
void usartTargetConfigure(uartPort_t *);
usartTargetConfigure(uartPort);
#endif

View File

@ -36,8 +36,8 @@
#include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h"
uartDevice_t uartDevice[UARTDEV_COUNT]; // Only those configured in target.h
uartDevice_t *uartDevmap[UARTDEV_COUNT_MAX]; // Full array
FAST_RAM uartDevice_t uartDevice[UARTDEV_COUNT]; // Only those configured in target.h
FAST_RAM uartDevice_t *uartDevmap[UARTDEV_COUNT_MAX]; // Full array
void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig)
{

View File

@ -846,7 +846,7 @@ static void subTaskPidController(timeUs_t currentTimeUs)
#endif
}
static void subTaskMainSubprocesses(timeUs_t currentTimeUs)
static NOINLINE void subTaskMainSubprocesses(timeUs_t currentTimeUs)
{
uint32_t startTime = 0;
if (debugMode == DEBUG_PIDLOOP) {
@ -956,7 +956,7 @@ static void subTaskMotorUpdate(timeUs_t currentTimeUs)
}
// Function for loop trigger
void taskMainPidLoop(timeUs_t currentTimeUs)
FAST_CODE void taskMainPidLoop(timeUs_t currentTimeUs)
{
static uint32_t pidUpdateCounter = 0;

View File

@ -177,7 +177,7 @@ static void checkForThrottleErrorResetState(uint16_t rxRefreshRate)
}
}
void processRcCommand(void)
FAST_CODE NOINLINE void processRcCommand(void)
{
static float rcCommandInterp[4] = { 0, 0, 0, 0 };
static float rcStepSize[4] = { 0, 0, 0, 0 };
@ -267,7 +267,7 @@ void processRcCommand(void)
}
}
void updateRcCommands(void)
FAST_CODE NOINLINE void updateRcCommands(void)
{
// PITCH & ROLL only dynamic PID adjustment, depending on throttle value
int32_t prop;

View File

@ -732,7 +732,7 @@ float applyThrottleLimit(float throttle)
return throttle;
}
void mixTable(timeUs_t currentTimeUs, uint8_t vbatPidCompensation)
NOINLINE void mixTable(timeUs_t currentTimeUs, uint8_t vbatPidCompensation)
{
if (isFlipOverAfterCrashMode()) {
applyFlipOverAfterCrashModeToMotors();

View File

@ -24,9 +24,19 @@
#include "scheduler/scheduler.h"
void run(void);
int main(void)
{
init();
run();
return 0;
}
void FAST_CODE NOINLINE run(void)
{
while (true) {
scheduler();
processLoopback();
@ -34,5 +44,4 @@ int main(void)
delayMicroseconds_real(50); // max rate 20kHz
#endif
}
return 0;
}

View File

@ -17,6 +17,8 @@
#pragma once
#define NOINLINE __attribute__((noinline))
#if !defined(UNIT_TEST) && !defined(SITL) && !(USBD_DEBUG_LEVEL > 0)
#pragma GCC poison sprintf snprintf
#endif

View File

@ -942,7 +942,7 @@ static void checkForOverflow(gyroSensor_t *gyroSensor, timeUs_t currentTimeUs)
#endif // USE_GYRO_OVERFLOW_CHECK
}
static FAST_CODE void gyroUpdateSensor(gyroSensor_t *gyroSensor, timeUs_t currentTimeUs)
static FAST_CODE NOINLINE void gyroUpdateSensor(gyroSensor_t *gyroSensor, timeUs_t currentTimeUs)
{
if (!gyroSensor->gyroDev.readFn(&gyroSensor->gyroDev)) {
return;

View File

@ -56,6 +56,10 @@ defined in linker script */
.word _sbss
/* end address for the .bss section. defined in linker script */
.word _ebss
/* start address for the .fastram_bss section. defined in linker script */
.word __fastram_bss_start__
/* end address for the .fastram_bss section. defined in linker script */
.word __fastram_bss_end__
/* stack used for SystemInit_ExtMemCtl; always internal RAM used */
/**
@ -98,6 +102,7 @@ LoopCopyDataInit:
adds r2, r0, r1
cmp r2, r3
bcc CopyDataInit
ldr r2, =_sbss
b LoopFillZerobss
/* Zero fill the bss segment. */
@ -110,6 +115,18 @@ LoopFillZerobss:
cmp r2, r3
bcc FillZerobss
ldr r2, =__fastram_bss_start__
b LoopFillZerofastram_bss
/* Zero fill the fastram_bss segment. */
FillZerofastram_bss:
movs r3, #0
str r3, [r2], #4
LoopFillZerofastram_bss:
ldr r3, = __fastram_bss_end__
cmp r2, r3
bcc FillZerofastram_bss
/* Mark the heap and stack */
ldr r2, =_heap_stack_begin
b LoopMarkHeapStack

View File

@ -62,6 +62,10 @@ defined in linker script */
.word _sbss
/* end address for the .bss section. defined in linker script */
.word _ebss
/* start address for the .fastram_bss section. defined in linker script */
.word _sfastram_bss
/* end address for the .fastram_bss section. defined in linker script */
.word _efastram_bss
/* stack used for SystemInit_ExtMemCtl; always internal RAM used */
/**
@ -95,6 +99,7 @@ LoopCopyDataInit:
adds r2, r0, r1
cmp r2, r3
bcc CopyDataInit
ldr r2, =_sbss
b LoopFillZerobss
/* Zero fill the bss segment. */
@ -107,10 +112,32 @@ LoopFillZerobss:
cmp r2, r3
bcc FillZerobss
ldr r2, =_ssram2
b LoopFillZerosram2
/* Zero fill the sram2 segment. */
FillZerosram2:
movs r3, #0
str r3, [r2], #4
LoopFillZerosram2:
ldr r3, = _esram2
cmp r2, r3
bcc FillZerosram2
ldr r2, =_sfastram_bss
b LoopFillZerofastram_bss
/* Zero fill the fastram_bss segment. */
FillZerofastram_bss:
movs r3, #0
str r3, [r2], #4
LoopFillZerofastram_bss:
ldr r3, = _efastram_bss
cmp r2, r3
bcc FillZerofastram_bss
/* Call the clock system intitialization function.*/
bl SystemInit
/* Call static constructors */
// bl __libc_init_array
/* Call the application's entry point.*/
bl main
bx lr

View File

@ -62,6 +62,10 @@ defined in linker script */
.word _sbss
/* end address for the .bss section. defined in linker script */
.word _ebss
/* start address for the .fastram_bss section. defined in linker script */
.word _sfastram_bss
/* end address for the .fastram_bss section. defined in linker script */
.word _efastram_bss
/* stack used for SystemInit_ExtMemCtl; always internal RAM used */
/**
@ -95,6 +99,7 @@ LoopCopyDataInit:
adds r2, r0, r1
cmp r2, r3
bcc CopyDataInit
ldr r2, =_sbss
b LoopFillZerobss
/* Zero fill the bss segment. */
@ -107,10 +112,32 @@ LoopFillZerobss:
cmp r2, r3
bcc FillZerobss
ldr r2, =_ssram2
b LoopFillZerosram2
/* Zero fill the sram2 segment. */
FillZerosram2:
movs r3, #0
str r3, [r2], #4
LoopFillZerosram2:
ldr r3, = _esram2
cmp r2, r3
bcc FillZerosram2
ldr r2, =_sfastram_bss
b LoopFillZerofastram_bss
/* Zero fill the fastram_bss segment. */
FillZerofastram_bss:
movs r3, #0
str r3, [r2], #4
LoopFillZerofastram_bss:
ldr r3, = _efastram_bss
cmp r2, r3
bcc FillZerofastram_bss
/* Call the clock system initialization function.*/
bl SystemInit
/* Call static constructors */
// bl __libc_init_array
/* Call the application's entry point.*/
bl main
bx lr

View File

@ -62,6 +62,10 @@ defined in linker script */
.word _sbss
/* end address for the .bss section. defined in linker script */
.word _ebss
/* start address for the .fastram_bss section. defined in linker script */
.word _sfastram_bss
/* end address for the .fastram_bss section. defined in linker script */
.word _efastram_bss
/* stack used for SystemInit_ExtMemCtl; always internal RAM used */
/**
@ -95,6 +99,7 @@ LoopCopyDataInit:
adds r2, r0, r1
cmp r2, r3
bcc CopyDataInit
ldr r2, =_sbss
b LoopFillZerobss
/* Zero fill the bss segment. */
@ -107,10 +112,32 @@ LoopFillZerobss:
cmp r2, r3
bcc FillZerobss
ldr r2, =_ssram2
b LoopFillZerosram2
/* Zero fill the sram2 segment. */
FillZerosram2:
movs r3, #0
str r3, [r2], #4
LoopFillZerosram2:
ldr r3, = _esram2
cmp r2, r3
bcc FillZerosram2
ldr r2, =_sfastram_bss
b LoopFillZerofastram_bss
/* Zero fill the fastram_bss segment. */
FillZerofastram_bss:
movs r3, #0
str r3, [r2], #4
LoopFillZerofastram_bss:
ldr r3, = _efastram_bss
cmp r2, r3
bcc FillZerofastram_bss
/* Call the clock system initialization function.*/
bl SystemInit
/* Call static constructors */
// bl __libc_init_array
/* Call the application's entry point.*/
bl main
bx lr

View File

@ -33,7 +33,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1), // PWM1 - DMA1_ST6 D(1, 7, 3),D(1, 6, 3)
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 1), // PWM2 - DMA2_ST2 D(2, 4, 7),D(2, 2, 0)
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0), // PWM3 - DMA1_ST1 D(1, 1, 3)
DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR, 0, 0), // PWM4 - DMA1_ST2 D(1, 2, 5)
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // PWM4 - DMA1_ST2 D(1, 2, 5)
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 2), // PWM5 - DMA2_ST3 D(2, 6, 0),D(2, 1, 6),D(2, 3, 6)
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // PWM6 - DMA1_ST0 D(1, 0, 2)

View File

@ -20,6 +20,8 @@
#define USBD_PRODUCT_STRING "CLRACINGF7"
#define ENABLE_DSHOT_DMAR true
#define LED0_PIN PB0
#define USE_BEEPER
#define BEEPER_PIN PB4

View File

@ -24,13 +24,15 @@ MEMORY
FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 480K /*main fw*/
TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 192K
SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 176K
SRAM2 (rwx) : ORIGIN = 0x2003C000, LENGTH = 16K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
/* note TCM could be used for stack */
REGION_ALIAS("STACKRAM", TCM)
REGION_ALIAS("FASTRAM", TCM)
REGION_ALIAS("RAM", SRAM1)
/* Entry Point */
@ -164,6 +166,35 @@ SECTIONS
__bss_end__ = _ebss;
} >RAM
/* Uninitialized data section */
. = ALIGN(4);
.sram2 (NOLOAD) :
{
/* This is used by the startup in order to initialize the .sram2 secion */
_ssram2 = .; /* define a global symbol at sram2 start */
__sram2_start__ = _ssram2;
*(.sram2)
*(SORT_BY_ALIGNMENT(.sram2*))
*(COMMON)
. = ALIGN(4);
_esram2 = .; /* define a global symbol at sram2 end */
__sram2_end__ = _esram2;
} >SRAM2
. = ALIGN(4);
.fastram_bss (NOLOAD) :
{
_sfastram_bss = .;
__fastram_bss_start__ = _sfastram_bss;
*(.fastram_bss)
*(SORT_BY_ALIGNMENT(.fastram_bss*))
. = ALIGN(4);
_efastram_bss = .;
__fastram_bss_end__ = _efastram_bss;
} >FASTRAM
/* User_heap_stack section, used to check that there is enough RAM left */
_heap_stack_end = ORIGIN(STACKRAM)+LENGTH(STACKRAM) - 8; /* 8 bytes to allow for alignment */
_heap_stack_begin = _heap_stack_end - _Min_Stack_Size - _Min_Heap_Size;

View File

@ -27,7 +27,7 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR, 0, 0), // S1 DMA1_ST4
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0), // S1 DMA1_ST4
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 0), // S2 DMA2_ST3
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // S3 DMA2_ST4
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // S4 DMA2_ST7

View File

@ -21,6 +21,8 @@
#define USBD_PRODUCT_STRING "MatekF7"
#define ENABLE_DSHOT_DMAR true
#define LED0_PIN PB9
#define LED1_PIN PA14

View File

@ -57,6 +57,5 @@ void targetConfiguration(void)
telemetryConfigMutable()->telemetry_inverted = 1;
telemetryConfigMutable()->halfDuplex = 1;
#endif
}
#endif

View File

@ -30,10 +30,18 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM | TIM_USE_PWM, 0, 0), // PPM / PWM1 / UART2 RX
DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM, 0, 0), // PPM / PWM2 / UART2 TX
#if (SPRACINGF7DUAL_REV <= 1)
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 0), // ESC 1
#else
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // ESC 1
#endif
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0), // ESC 2
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // ESC 3
#if (SPRACINGF7DUAL_REV <= 1)
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // ESC 4
#else
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 0), // ESC 4
#endif
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // ESC 5 / Conflicts with USART5_RX / SPI3_RX - SPI3_RX can be mapped to DMA1_ST3_CH0
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // ESC 6 / Conflicts with USART3_RX

View File

@ -31,6 +31,8 @@
#define USE_DUAL_GYRO
//#define DEBUG_MODE DEBUG_DUAL_GYRO_DIFF
#define ENABLE_DSHOT_DMAR true
#define LED0_PIN PC4
#define USE_BEEPER
@ -178,9 +180,9 @@
//#define ADC_INSTANCE ADC1
//#define ADC1_DMA_STREAM DMA2_Stream0
// Using ADC3 frees up DMA2_Stream0 for SPI1_RX
// Using ADC3 frees up DMA2_Stream0 for SPI1_RX (not necessarily, SPI1_RX has DMA2_Stream2 as well)
#define ADC_INSTANCE ADC3
#define ADC3_DMA_STREAM DMA2_Stream1
#define ADC3_DMA_STREAM DMA2_Stream0
#define VBAT_ADC_PIN PC1
#define CURRENT_METER_ADC_PIN PC2

View File

@ -45,6 +45,10 @@
#endif
#ifdef STM32F4
#define USE_SRAM2
#if defined(STM32F40_41xxx)
#define USE_FAST_RAM
#endif
#define USE_DSHOT
#define I2C3_OVERCLOCK true
#define USE_GYRO_DATA_ANALYSE
@ -59,10 +63,10 @@
#endif // STM32F4
#ifdef STM32F722xx
#define USE_ITCM_RAM
#endif
#ifdef STM32F7
#define USE_SRAM2
#define USE_ITCM_RAM
#define USE_FAST_RAM
#define USE_DSHOT
#define I2C3_OVERCLOCK true
#define I2C4_OVERCLOCK true
@ -94,11 +98,7 @@
#endif // USE_ITCM_RAM
#ifdef USE_FAST_RAM
#ifdef __APPLE__
#define FAST_RAM __attribute__ ((section("__DATA,__.fastram_bss"), aligned(4)))
#else
#define FAST_RAM __attribute__ ((section(".fastram_bss"), aligned(4)))
#endif
#else
#define FAST_RAM
#endif // USE_FAST_RAM
@ -108,6 +108,12 @@
#define PERSISTENT __attribute__ ((section(".persistent_data"), aligned(4)))
#endif
#ifdef USE_SRAM2
#define SRAM2 __attribute__ ((section(".sram2"), aligned(4)))
#else
#define SRAM2
#endif
#define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot
#define USE_CLI
#define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values

View File

@ -22,26 +22,29 @@ ENTRY(Reset_Handler)
/* Specify the memory areas */
MEMORY
{
ITCM_ISR (rx) : ORIGIN = 0x00000000, LENGTH = 1K
ITCM_RAM (rx) : ORIGIN = 0x00000400, LENGTH = 15K
ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K
ITCMFL (rx) : ORIGIN = 0x00200000, LENGTH = 16K
ITCMFL1 (rx) : ORIGIN = 0x00208000, LENGTH = 480K
ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 16K
/* config occupies the entire flash sector 1 for the ease of erasure, 16K on F72x */
ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00204000, LENGTH = 16K
ITCM_FLASH1 (rx) : ORIGIN = 0x00208000, LENGTH = 480K
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
AXIM_FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K
TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 176K
SRAM2 (rwx) : ORIGIN = 0x2003C000, LENGTH = 16K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
REGION_ALIAS("FLASH", AXIM_FLASH)
REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CONFIG)
REGION_ALIAS("FLASH1", AXIM_FLASH1)
REGION_ALIAS("STACKRAM", DTCM_RAM)
REGION_ALIAS("FASTRAM", DTCM_RAM)
REGION_ALIAS("RAM", SRAM1)
/* note TCM could be used for stack */
REGION_ALIAS("STACKRAM", TCM)
REGION_ALIAS("FASTRAM", TCM)
INCLUDE "stm32_flash_f7_split.ld"

View File

@ -1,40 +0,0 @@
/*
*****************************************************************************
**
** File : stm32_flash_f745.ld
**
** Abstract : Linker script for STM32F745VGTx Device with
** 1024KByte FLASH, 320KByte RAM
**
*****************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
/*
0x00000000 to 0x00003FFF 16K TCM RAM,
0x08000000 to 0x080FFFFF 1024K full flash,
0x08000000 to 0x08007FFF 32K isr vector, startup code,
0x08008000 to 0x0800FFFF 32K config, // FLASH_Sector_1
0x08010000 to 0x080FFFFF 960K firmware,
*/
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K
FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K
FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 960K
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 16K
TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 256K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
/* note CCM could be used for stack */
REGION_ALIAS("STACKRAM", TCM)
REGION_ALIAS("FASTRAM", TCM)
INCLUDE "stm32_flash_f7_split.ld"

View File

@ -1,40 +0,0 @@
/*
*****************************************************************************
**
** File : stm32_flash_f746.ld
**
** Abstract : Linker script for STM32F746VGTx Device with
** 1024KByte FLASH, 320KByte RAM
**
*****************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
/*
0x00000000 to 0x00003FFF 16K TCM RAM,
0x08000000 to 0x080FFFFF 1024K full flash,
0x08000000 to 0x08007FFF 32K isr vector, startup code,
0x08008000 to 0x0800FFFF 32K config, // FLASH_Sector_1
0x08010000 to 0x080FFFFF 960K firmware,
*/
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K
FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K
FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 960K
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 16K
TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 256K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
/* note CCM could be used for stack */
REGION_ALIAS("STACKRAM", TCM)
REGION_ALIAS("FASTRAM", TCM)
INCLUDE "stm32_flash_f7_split.ld"

View File

@ -0,0 +1,52 @@
/*
*****************************************************************************
**
** File : stm32_flash_f74x.ld
**
** Abstract : Linker script for STM32F74xVGTx Device with
** 1024KByte FLASH, 320KByte RAM
**
*****************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
/*
0x00000000 to 0x00003FFF 16K TCM RAM,
0x08000000 to 0x080FFFFF 1024K full flash,
0x08000000 to 0x08007FFF 32K isr vector, startup code,
0x08008000 to 0x0800FFFF 32K config, // FLASH_Sector_1
0x08010000 to 0x080FFFFF 960K firmware,
*/
/* Specify the memory areas */
MEMORY
{
ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K
ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K
/* config occupies the entire flash sector 1 for the ease of erasure, 32K on F74x */
ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K
ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 960K
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K
AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 960K
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 240K
SRAM2 (rwx) : ORIGIN = 0x2004C000, LENGTH = 16K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
REGION_ALIAS("FLASH", ITCM_FLASH)
REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CONFIG)
REGION_ALIAS("FLASH1", ITCM_FLASH1)
REGION_ALIAS("STACKRAM", DTCM_RAM)
REGION_ALIAS("FASTRAM", DTCM_RAM)
REGION_ALIAS("RAM", SRAM1)
INCLUDE "stm32_flash_f7_split.ld"

View File

@ -32,20 +32,7 @@ SECTIONS
PROVIDE (isr_vector_table_base = .);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >FLASH
/* Critical program code goes into ITCM RAM */
/* Copy specific fast-executing code to ITCM RAM */
tcm_code = LOADADDR(.tcm_code);
.tcm_code :
{
. = ALIGN(4);
tcm_code_start = .;
*(.tcm_code)
*(.tcm_code*)
. = ALIGN(4);
tcm_code_end = .;
} >ITCM_RAM AT >FLASH1
} >FLASH AT >AXIM_FLASH
/* The program code and other data goes into FLASH */
.text :
@ -64,7 +51,20 @@ SECTIONS
. = ALIGN(4);
_etext = .; /* define a global symbols at end of code */
} >FLASH1
} >FLASH1 AT >AXIM_FLASH1
/* Critical program code goes into ITCM RAM */
/* Copy specific fast-executing code to ITCM RAM */
tcm_code = LOADADDR(.tcm_code);
.tcm_code :
{
. = ALIGN(4);
tcm_code_start = .;
*(.tcm_code)
*(.tcm_code*)
. = ALIGN(4);
tcm_code_end = .;
} >ITCM_RAM AT >AXIM_FLASH1
.ARM.extab :
{
@ -75,30 +75,7 @@ SECTIONS
{
__exidx_start = .;
*(.ARM.exidx*) __exidx_end = .;
} >FLASH
.preinit_array :
{
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
} >FLASH
.init_array :
{
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
} >FLASH
.fini_array :
{
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(.fini_array*))
KEEP (*(SORT(.fini_array.*)))
PROVIDE_HIDDEN (__fini_array_end = .);
} >FLASH
} >FLASH AT >AXIM_FLASH
.pg_registry :
{
@ -106,14 +83,14 @@ SECTIONS
KEEP (*(.pg_registry))
KEEP (*(SORT(.pg_registry.*)))
PROVIDE_HIDDEN (__pg_registry_end = .);
} >FLASH
} >FLASH AT >AXIM_FLASH
.pg_resetdata :
{
PROVIDE_HIDDEN (__pg_resetdata_start = .);
KEEP (*(.pg_resetdata))
PROVIDE_HIDDEN (__pg_resetdata_end = .);
} >FLASH
} >FLASH AT >AXIM_FLASH
/* used by the startup to initialize data */
_sidata = .;
@ -128,11 +105,11 @@ SECTIONS
. = ALIGN(4);
_edata = .; /* define a global symbol at data end */
} >RAM AT >FLASH
} >RAM AT >AXIM_FLASH
/* Uninitialized data section */
. = ALIGN(4);
.bss :
.bss (NOLOAD) :
{
/* This is used by the startup in order to initialize the .bss secion */
_sbss = .; /* define a global symbol at bss start */
@ -146,6 +123,35 @@ SECTIONS
__bss_end__ = _ebss;
} >RAM
/* Uninitialized data section */
. = ALIGN(4);
.sram2 (NOLOAD) :
{
/* This is used by the startup in order to initialize the .sram2 secion */
_ssram2 = .; /* define a global symbol at sram2 start */
__sram2_start__ = _ssram2;
*(.sram2)
*(SORT_BY_ALIGNMENT(.sram2*))
*(COMMON)
. = ALIGN(4);
_esram2 = .; /* define a global symbol at sram2 end */
__sram2_end__ = _esram2;
} >SRAM2
. = ALIGN(4);
.fastram_bss (NOLOAD) :
{
_sfastram_bss = .;
__fastram_bss_start__ = _sfastram_bss;
*(.fastram_bss)
*(SORT_BY_ALIGNMENT(.fastram_bss*))
. = ALIGN(4);
_efastram_bss = .;
__fastram_bss_end__ = _efastram_bss;
} >FASTRAM
/* User_heap_stack section, used to check that there is enough RAM left */
_heap_stack_end = ORIGIN(STACKRAM)+LENGTH(STACKRAM) - 8; /* 8 bytes to allow for alignment */
_heap_stack_begin = _heap_stack_end - _Min_Stack_Size - _Min_Heap_Size;

View File

@ -158,10 +158,13 @@
#define VDD_VALUE ((uint32_t)3300U) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY ((uint32_t)0U) /*!< tick interrupt priority */
#define USE_RTOS 0U
/* @todo to save a bit of power, ART and ART Prefetch should only be enabled
when running from ITCM-FLASH, while the instruction cache - only when running
from AXIM-FLASH */
#define PREFETCH_ENABLE 1U
#define ART_ACCLERATOR_ENABLE 1U /* To enable instruction cache and prefetch */
#define INSTRUCTION_CACHE_ENABLE 1U
#define DATA_CACHE_ENABLE 0U
#define DATA_CACHE_ENABLE 1U
/* ########################## Assert Selection ############################## */
/**

View File

@ -294,7 +294,7 @@ void OverclockRebootIfNecessary(uint32_t overclockLevel)
const pllConfig_t * const pll = overclockLevels + overclockLevel;
// Reboot to adjust overclock frequency
if (SystemCoreClock != ((pll->n / pll->p) * 1000000UL)) {
if (SystemCoreClock != (pll->n / pll->p) * 1000000) {
REQUEST_OVERCLOCK = REQUEST_OVERCLOCK_MAGIC_COOKIE;
CURRENT_OVERCLOCK_LEVEL = overclockLevel;
__disable_irq();
@ -366,7 +366,7 @@ void SystemInit(void)
/* Configure the system clock to specified frequency */
SystemClock_Config();
if (SystemCoreClock != (pll_n / pll_p) * 1000000UL) {
if (SystemCoreClock != (pll_n / pll_p) * 1000000) {
// There is a mismatch between the configured clock and the expected clock in portable.h
while (1);
}

View File

@ -25,6 +25,7 @@
#define U_ID_1 1
#define U_ID_2 2
#define NOINLINE
#define FAST_CODE
#define FAST_RAM