diff --git a/src/main/config/config.c b/src/main/config/config.c
index b5025cd6f..dce58b283 100755
--- a/src/main/config/config.c
+++ b/src/main/config/config.c
@@ -37,6 +37,7 @@
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/gyro_sync.h"
+#include "drivers/pwm_output.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
@@ -121,8 +122,14 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
#endif
#if defined(FLASH_SIZE)
+#if defined(STM32F40_41xxx)
+#define FLASH_PAGE_COUNT 4 // just to make calculations work
+#elif defined (STM32F411xE)
+#define FLASH_PAGE_COUNT 4 // just to make calculations work
+#else
#define FLASH_PAGE_COUNT ((FLASH_SIZE * 0x400) / FLASH_PAGE_SIZE)
#endif
+#endif
#if !defined(FLASH_PAGE_SIZE)
#error "Flash page size not defined for target."
@@ -148,6 +155,7 @@ size_t custom_flash_memory_address = 0;
#define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG))
#endif
#endif
+
master_t masterConfig; // master config struct with data independent from profiles
profile_t *currentProfile;
static uint32_t activeFeaturesLatch = 0;
@@ -322,7 +330,8 @@ void resetSerialConfig(serialConfig_t *serialConfig)
serialConfig->reboot_character = 'R';
}
-static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) {
+static void resetControlRateConfig(controlRateConfig_t *controlRateConfig)
+{
controlRateConfig->rcRate8 = 100;
controlRateConfig->rcYawRate8 = 100;
controlRateConfig->rcExpo8 = 10;
@@ -338,14 +347,16 @@ static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) {
}
-void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) {
+void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig)
+{
rcControlsConfig->deadband = 0;
rcControlsConfig->yaw_deadband = 0;
rcControlsConfig->alt_hold_deadband = 40;
rcControlsConfig->alt_hold_fast_change = 1;
}
-void resetMixerConfig(mixerConfig_t *mixerConfig) {
+void resetMixerConfig(mixerConfig_t *mixerConfig)
+{
mixerConfig->yaw_motor_direction = 1;
#ifdef USE_SERVOS
mixerConfig->tri_unarmed_servo = 1;
@@ -371,14 +382,15 @@ uint8_t getCurrentControlRateProfile(void)
return currentControlRateProfileIndex;
}
-static void setControlRateProfile(uint8_t profileIndex) {
+static void setControlRateProfile(uint8_t profileIndex)
+{
currentControlRateProfileIndex = profileIndex;
masterConfig.profile[getCurrentProfile()].activeRateProfile = profileIndex;
currentControlRateProfile = &masterConfig.profile[getCurrentProfile()].controlRateProfile[profileIndex];
}
-
-controlRateConfig_t *getControlRateConfig(uint8_t profileIndex) {
+controlRateConfig_t *getControlRateConfig(uint8_t profileIndex)
+{
return &masterConfig.profile[profileIndex].controlRateProfile[masterConfig.profile[profileIndex].activeRateProfile];
}
@@ -399,7 +411,7 @@ static void resetConf(void)
masterConfig.version = EEPROM_CONF_VERSION;
masterConfig.mixerMode = MIXER_QUADX;
featureClearAll();
-#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE) || defined(DOGE) || defined(SINGULARITY)
+#ifdef CONFIG_RX_PPM
featureSet(FEATURE_RX_PPM);
#endif
@@ -474,7 +486,11 @@ static void resetConf(void)
masterConfig.rxConfig.rssi_ppm_invert = 0;
masterConfig.rxConfig.rcSmoothing = 0;
masterConfig.rxConfig.fpvCamAngleDegrees = 0;
+#ifdef STM32F4
+ masterConfig.rxConfig.max_aux_channel = 99;
+#else
masterConfig.rxConfig.max_aux_channel = 6;
+#endif
masterConfig.rxConfig.airModeActivateThreshold = 1350;
resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
@@ -496,12 +512,14 @@ static void resetConf(void)
#ifdef BRUSHED_MOTORS
masterConfig.motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE;
+ masterConfig.motor_pwm_protocol = PWM_TYPE_BRUSHED;
#else
masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
+ masterConfig.motor_pwm_protocol = PWM_TYPE_ONESHOT125;
#endif
masterConfig.servo_pwm_rate = 50;
- masterConfig.fast_pwm_protocol = 1;
- masterConfig.use_unsyncedPwm = 0;
+ masterConfig.use_unsyncedPwm = false;
+
#ifdef CC3D
masterConfig.use_buzzer_p6 = 0;
#endif
@@ -628,8 +646,11 @@ static void resetConf(void)
featureSet(FEATURE_TELEMETRY);
#endif
- // alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets
-#ifdef ALIENFLIGHT
+#if defined(TARGET_CONFIG)
+ targetConfiguration(&masterConfig);
+#endif
+
+#if defined(ALIENFLIGHT)
featureSet(FEATURE_RX_SERIAL);
featureSet(FEATURE_MOTOR_STOP);
featureClear(FEATURE_ONESHOT125);
@@ -1000,10 +1021,11 @@ void writeEEPROM(void)
// write it
FLASH_Unlock();
while (attemptsRemaining--) {
-#ifdef STM32F303
+#if defined(STM32F4)
+ FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
+#elif defined(STM32F303)
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPERR);
-#endif
-#ifdef STM32F10X
+#elif defined(STM32F10X)
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
#endif
for (wordOffset = 0; wordOffset < sizeof(master_t); wordOffset += 4) {
diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h
index ee3412202..b06553335 100644
--- a/src/main/config/config_master.h
+++ b/src/main/config/config_master.h
@@ -34,7 +34,7 @@ typedef struct master_t {
uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
- uint8_t fast_pwm_protocol; // Pwm Protocol
+ uint8_t motor_pwm_protocol; // Pwm Protocol
uint8_t use_unsyncedPwm; // unsync fast pwm protocol from PID loop
#ifdef USE_SERVOS
diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c
index bfe63dbdd..316a7119c 100644
--- a/src/main/drivers/accgyro_mpu.c
+++ b/src/main/drivers/accgyro_mpu.c
@@ -154,7 +154,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(void)
}
#endif
-#ifdef USE_GYRO_SPI_MPU9250
+#ifdef USE_GYRO_SPI_MPU9250
if (mpu9250SpiDetect()) {
mpuDetectionResult.sensor = MPU_9250_SPI;
mpuConfiguration.gyroReadXRegister = MPU_RA_GYRO_XOUT_H;
diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c
index 763c10e11..5949cb0ff 100755
--- a/src/main/drivers/pwm_mapping.c
+++ b/src/main/drivers/pwm_mapping.c
@@ -31,7 +31,7 @@
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
-void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint8_t useUnsyncedPwm, uint16_t idlePulse);
+void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
/*
@@ -967,7 +967,7 @@ if (init->useBuzzerP6) {
if (type == MAP_TO_PPM_INPUT) {
#if defined(SPARKY) || defined(ALIENFLIGHTF3)
- if (init->useFastPwm || isMotorBrushed(init->motorPwmRate)) {
+ if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED)) {
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2);
}
#endif
@@ -978,16 +978,16 @@ if (init->useBuzzerP6) {
} else if (type == MAP_TO_MOTOR_OUTPUT) {
#ifdef CC3D
- if (init->useFastPwm || isMotorBrushed(init->motorPwmRate)){
+ if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED) {
// Skip it if it would cause PPM capture timer to be reconfigured or manually overflowed
if (timerHardwarePtr->tim == TIM2)
continue;
}
#endif
if (init->useFastPwm) {
- pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->pwmProtocolType, init->motorPwmRate, init->useUnsyncedPwm, init->idlePulse);
+ pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->pwmProtocolType, init->motorPwmRate, init->idlePulse);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ;
- } else if (isMotorBrushed(init->motorPwmRate)) {
+ } else if (init->pwmProtocolType == PWM_TYPE_BRUSHED) {
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_MOTOR_MODE_BRUSHED | PWM_PF_OUTPUT_PROTOCOL_PWM;
} else {
diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h
index da5762ec6..0facb7c0e 100644
--- a/src/main/drivers/pwm_mapping.h
+++ b/src/main/drivers/pwm_mapping.h
@@ -136,7 +136,11 @@ enum {
PWM13,
PWM14,
PWM15,
- PWM16
+ PWM16,
+ PWM17,
+ PWM18,
+ PWM19,
+ PWM20
};
extern const uint16_t multiPPM[];
diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c
index 56759cbd4..03bd7bbe3 100644
--- a/src/main/drivers/pwm_output.c
+++ b/src/main/drivers/pwm_output.c
@@ -100,8 +100,8 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
configTimeBase(timerHardware->tim, period, mhz);
pwmGPIOConfig(timerHardware->gpio, timerHardware->pin, Mode_AF_PP);
-
pwmOCConfig(timerHardware->tim, timerHardware->channel, value);
+
if (timerHardware->outputEnable)
TIM_CtrlPWMOutputs(timerHardware->tim, ENABLE);
TIM_Cmd(timerHardware->tim, ENABLE);
@@ -187,11 +187,6 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount)
}
}
-bool isMotorBrushed(uint16_t motorPwmRate)
-{
- return (motorPwmRate > 500);
-}
-
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse)
{
uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000;
@@ -206,7 +201,7 @@ void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motor
motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
}
-void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint8_t useUnsyncedPwm, uint16_t idlePulse)
+void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint16_t idlePulse)
{
uint32_t timerMhzCounter;
@@ -222,7 +217,7 @@ void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIn
timerMhzCounter = MULTISHOT_TIMER_MHZ;
}
- if (useUnsyncedPwm) {
+ if (motorPwmRate > 0) {
uint32_t hz = timerMhzCounter * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, hz / motorPwmRate, idlePulse);
} else {
diff --git a/src/main/drivers/pwm_output.h b/src/main/drivers/pwm_output.h
index 060d7f388..c89e7fa80 100644
--- a/src/main/drivers/pwm_output.h
+++ b/src/main/drivers/pwm_output.h
@@ -18,11 +18,12 @@
#pragma once
typedef enum {
- PWM_TYPE_CONVENTIONAL = 0,
- PWM_TYPE_ONESHOT125,
- PWM_TYPE_ONESHOT42,
- PWM_TYPE_MULTISHOT
-} FastPwmProtocolTypes_e;
+ PWM_TYPE_CONVENTIONAL = 0,
+ PWM_TYPE_ONESHOT125,
+ PWM_TYPE_ONESHOT42,
+ PWM_TYPE_MULTISHOT,
+ PWM_TYPE_BRUSHED
+} motorPwmProtocolTypes_e;
void pwmWriteMotor(uint8_t index, uint16_t value);
void pwmShutdownPulsesForAllMotors(uint8_t motorCount);
@@ -30,6 +31,5 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount);
void pwmWriteServo(uint8_t index, uint16_t value);
-bool isMotorBrushed(uint16_t motorPwmRate);
void pwmDisableMotors(void);
void pwmEnableMotors(void);
diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c
index 95e2b8c9a..4b5102421 100644
--- a/src/main/drivers/serial_uart.c
+++ b/src/main/drivers/serial_uart.c
@@ -108,6 +108,19 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
} else if (USARTx == USART3) {
s = serialUSART3(baudRate, mode, options);
#endif
+#ifdef USE_USART4
+ } else if (USARTx == UART4) {
+ s = serialUSART4(baudRate, mode, options);
+#endif
+#ifdef USE_USART5
+ } else if (USARTx == UART5) {
+ s = serialUSART5(baudRate, mode, options);
+#endif
+#ifdef USE_USART6
+ } else if (USARTx == USART6) {
+ s = serialUSART6(baudRate, mode, options);
+#endif
+
} else {
return (serialPort_t *)s;
}
diff --git a/src/main/drivers/serial_uart.h b/src/main/drivers/serial_uart.h
index 1458c3aca..78b6d7042 100644
--- a/src/main/drivers/serial_uart.h
+++ b/src/main/drivers/serial_uart.h
@@ -29,6 +29,12 @@
#define UART2_TX_BUFFER_SIZE 256
#define UART3_RX_BUFFER_SIZE 256
#define UART3_TX_BUFFER_SIZE 256
+#define UART4_RX_BUFFER_SIZE 256
+#define UART4_TX_BUFFER_SIZE 256
+#define UART5_RX_BUFFER_SIZE 256
+#define UART5_TX_BUFFER_SIZE 256
+#define UART6_RX_BUFFER_SIZE 256
+#define UART6_TX_BUFFER_SIZE 256
typedef struct {
serialPort_t port;
diff --git a/src/main/drivers/serial_uart_impl.h b/src/main/drivers/serial_uart_impl.h
index 7ff2deb14..5b0c2b3e0 100644
--- a/src/main/drivers/serial_uart_impl.h
+++ b/src/main/drivers/serial_uart_impl.h
@@ -26,4 +26,7 @@ void uartStartTxDMA(uartPort_t *s);
uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options);
uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options);
uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options);
+uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t options);
+uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t options);
+uartPort_t *serialUSART6(uint32_t baudRate, portMode_t mode, portOptions_t options);
diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c
index bc52c6e3c..68935eb21 100755
--- a/src/main/drivers/timer.c
+++ b/src/main/drivers/timer.c
@@ -535,8 +535,24 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
// "The counter clock frequency (CK_CNT) is equal to f CK_PSC / (PSC[15:0] + 1)." - STM32F10x Reference Manual 14.4.11
// Thus for 1Mhz: 72000000 / 1000000 = 72, 72 - 1 = 71 = TIM_Prescaler
+#if defined (STM32F40_41xxx)
+ if (tim == TIM1 || tim == TIM8 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
+ TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
+ }
+ else {
+ TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 2 / ((uint32_t)mhz * 1000000)) - 1;
+ }
+#elif defined (STM32F411xE)
+ if (tim == TIM1 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
+ TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
+ }
+ else {
+ TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 2 / ((uint32_t)mhz * 1000000)) - 1;
+ }
+#else
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
-
+#endif
+
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
TIM_TimeBaseInit(tim, &TIM_TimeBaseStructure);
@@ -555,6 +571,19 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui
timerNVICConfigure(TIM1_UP_IRQn);
break;
#endif
+#if defined (STM32F40_41xxx)
+ case TIM1_CC_IRQn:
+ timerNVICConfigure(TIM1_UP_TIM10_IRQn);
+ break;
+ case TIM8_CC_IRQn:
+ timerNVICConfigure(TIM8_UP_TIM13_IRQn);
+ break;
+#endif
+#if defined (STM32F411xE)
+ case TIM1_CC_IRQn:
+ timerNVICConfigure(TIM1_UP_TIM10_IRQn);
+ break;
+#endif
#ifdef STM32F303xC
case TIM1_CC_IRQn:
timerNVICConfigure(TIM1_UP_TIM16_IRQn);
@@ -823,8 +852,6 @@ void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHig
}
}
-
-
static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
{
uint16_t capture;
@@ -917,6 +944,13 @@ _TIM_IRQ_HANDLER(TIM1_CC_IRQHandler, 1);
# if defined(STM32F10X)
_TIM_IRQ_HANDLER(TIM1_UP_IRQHandler, 1); // timer can't be shared
# endif
+# if defined(STM32F40_41xxx) || defined (STM32F411xE)
+# if USED_TIMERS & TIM_N(10)
+_TIM_IRQ_HANDLER2(TIM1_UP_TIM10_IRQHandler, 1, 10); // both timers are in use
+# else
+_TIM_IRQ_HANDLER(TIM1_UP_TIM10_IRQHandler, 1); // timer10 is not used
+# endif
+# endif
# ifdef STM32F303xC
# if USED_TIMERS & TIM_N(16)
_TIM_IRQ_HANDLER2(TIM1_UP_TIM16_IRQHandler, 1, 16); // both timers are in use
@@ -934,6 +968,9 @@ _TIM_IRQ_HANDLER(TIM3_IRQHandler, 3);
#if USED_TIMERS & TIM_N(4)
_TIM_IRQ_HANDLER(TIM4_IRQHandler, 4);
#endif
+#if USED_TIMERS & TIM_N(5)
+_TIM_IRQ_HANDLER(TIM5_IRQHandler, 5);
+#endif
#if USED_TIMERS & TIM_N(8)
_TIM_IRQ_HANDLER(TIM8_CC_IRQHandler, 8);
# if defined(STM32F10X_XL)
@@ -941,6 +978,24 @@ _TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler, 8);
# else // f10x_hd, f30x
_TIM_IRQ_HANDLER(TIM8_UP_IRQHandler, 8);
# endif
+# if defined(STM32F40_41xxx)
+# if USED_TIMERS & TIM_N(13)
+_TIM_IRQ_HANDLER2(TIM8_UP_TIM13_IRQHandler, 8, 13); // both timers are in use
+# else
+_TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler, 8); // timer13 is not used
+# endif
+# endif
+# if defined (STM32F411xE)
+# endif
+#endif
+#if USED_TIMERS & TIM_N(9)
+_TIM_IRQ_HANDLER(TIM1_BRK_TIM9_IRQHandler, 9);
+#endif
+# if USED_TIMERS & TIM_N(11)
+_TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM11_IRQHandler, 11);
+# endif
+#if USED_TIMERS & TIM_N(12)
+_TIM_IRQ_HANDLER(TIM8_BRK_TIM12_IRQHandler, 12);
#endif
#if USED_TIMERS & TIM_N(15)
_TIM_IRQ_HANDLER(TIM1_BRK_TIM15_IRQHandler, 15);
@@ -979,6 +1034,12 @@ void timerInit(void)
}
#endif
+#if defined(STM32F40_41xxx) || defined (STM32F411xE)
+ for (uint8_t timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
+ const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
+ GPIO_PinAFConfig(timerHardwarePtr->gpio, (uint16_t)timerHardwarePtr->gpioPinSource, timerHardwarePtr->alternateFunction);
+ }
+#endif
// initialize timer channel structures
for(int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
timerChannelInfo[i].type = TYPE_FREE;
diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c
index 100aeb62f..3cf003abe 100755
--- a/src/main/flight/mixer.c
+++ b/src/main/flight/mixer.c
@@ -633,15 +633,21 @@ void writeServos(void)
}
#endif
-void writeMotors(uint8_t fastPwmProtocol, uint8_t unsyncedPwm)
+static bool syncPwm = false;
+
+void syncMotors(bool enabled)
+{
+ syncPwm = enabled;
+}
+
+void writeMotors(void)
{
uint8_t i;
for (i = 0; i < motorCount; i++)
pwmWriteMotor(i, motor[i]);
-
- if (fastPwmProtocol && !unsyncedPwm) {
+ if (syncPwm) {
pwmCompleteOneshotMotorUpdate(motorCount);
}
}
@@ -653,7 +659,7 @@ void writeAllMotors(int16_t mc)
// Sends commands to all motors
for (i = 0; i < motorCount; i++)
motor[i] = mc;
- writeMotors(1,1);
+ writeMotors();
}
void stopMotors(void)
@@ -750,7 +756,7 @@ STATIC_UNIT_TESTED void servoMixer(void)
void mixTable(void)
{
- uint32_t i;
+ uint32_t i = 0;
fix12_t vbatCompensationFactor = 0;
static fix12_t mixReduction;
bool use_vbat_compensation = false;
diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h
index 8ccd45cb3..8828ba08b 100644
--- a/src/main/flight/mixer.h
+++ b/src/main/flight/mixer.h
@@ -213,6 +213,7 @@ int servoDirection(int servoIndex, int fromChannel);
#endif
void mixerResetDisarmedMotors(void);
void mixTable(void);
-void writeMotors(uint8_t fastPwmProtocol, uint8_t unsyncedPwm);
+void syncMotors(bool enabled);
+void writeMotors(void);
void stopMotors(void);
void StopPwmAllMotors(void);
diff --git a/src/main/io/serial.c b/src/main/io/serial.c
index 2765cfb57..a0b5122da 100644
--- a/src/main/io/serial.c
+++ b/src/main/io/serial.c
@@ -32,7 +32,7 @@
#include "drivers/serial_softserial.h"
#endif
-#if defined(USE_USART1) || defined(USE_USART2) || defined(USE_USART3)
+#if defined(USE_USART1) || defined(USE_USART2) || defined(USE_USART3) || defined(USE_USART4) || defined(USE_USART5) || defined(USE_USART6)
#include "drivers/serial_uart.h"
#endif
@@ -69,6 +69,15 @@ const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
#ifdef USE_USART3
SERIAL_PORT_USART3,
#endif
+#ifdef USE_USART4
+ SERIAL_PORT_USART4,
+#endif
+#ifdef USE_USART5
+ SERIAL_PORT_USART5,
+#endif
+#ifdef USE_USART6
+ SERIAL_PORT_USART6,
+#endif
#ifdef USE_SOFTSERIAL1
SERIAL_PORT_SOFTSERIAL1,
#endif
@@ -293,6 +302,21 @@ serialPort_t *openSerialPort(
serialPort = uartOpen(USART3, callback, baudRate, mode, options);
break;
#endif
+#ifdef USE_USART4
+ case SERIAL_PORT_USART4:
+ serialPort = uartOpen(UART4, callback, baudRate, mode, options);
+ break;
+#endif
+#ifdef USE_USART5
+ case SERIAL_PORT_USART5:
+ serialPort = uartOpen(USART5, callback, baudRate, mode, options);
+ break;
+#endif
+#ifdef USE_USART6
+ case SERIAL_PORT_USART6:
+ serialPort = uartOpen(USART6, callback, baudRate, mode, options);
+ break;
+#endif
#ifdef USE_SOFTSERIAL1
case SERIAL_PORT_SOFTSERIAL1:
serialPort = openSoftSerial(SOFTSERIAL1, callback, baudRate, options);
diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c
index dcea1a5af..834a774c9 100644
--- a/src/main/io/serial_cli.c
+++ b/src/main/io/serial_cli.c
@@ -452,7 +452,7 @@ static const char * const lookupTableSuperExpoYaw[] = {
};
static const char * const lookupTableFastPwm[] = {
- "OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT"
+ "OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED"
};
typedef struct lookupTableEntry_s {
@@ -481,7 +481,7 @@ typedef enum {
TABLE_MAG_HARDWARE,
TABLE_DEBUG,
TABLE_SUPEREXPO_YAW,
- TABLE_FAST_PWM,
+ TABLE_MOTOR_PWM_PROTOCOL,
} lookupTableIndex_e;
static const lookupTableEntry_t lookupTables[] = {
@@ -583,7 +583,8 @@ const clivalue_t valueTable[] = {
{ "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "unsynced_fast_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_unsyncedPwm, .config.lookup = { TABLE_OFF_ON } },
- { "fast_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.fast_pwm_protocol, .config.lookup = { TABLE_FAST_PWM } },
+ { "fast_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motor_pwm_protocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } },
+ { "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motor_pwm_protocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } },
#ifdef CC3D
{ "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } },
#endif
diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c
index a827db5d4..992709a1d 100644
--- a/src/main/io/serial_msp.c
+++ b/src/main/io/serial_msp.c
@@ -399,7 +399,7 @@ static void serializeSDCardSummaryReply(void)
#ifdef USE_SDCARD
uint8_t flags = 1 /* SD card supported */ ;
- uint8_t state;
+ uint8_t state = 0;
serialize8(flags);
diff --git a/src/main/main.c b/src/main/main.c
index bdb153074..ce704dfcf 100644
--- a/src/main/main.c
+++ b/src/main/main.c
@@ -329,20 +329,20 @@ void init(void)
pwm_params.servoPwmRate = masterConfig.servo_pwm_rate;
#endif
- if (masterConfig.fast_pwm_protocol == PWM_TYPE_ONESHOT125) {
+ if (masterConfig.motor_pwm_protocol == PWM_TYPE_ONESHOT125) {
featureSet(FEATURE_ONESHOT125);
} else {
featureClear(FEATURE_ONESHOT125);
}
- pwm_params.useFastPwm = (masterConfig.fast_pwm_protocol != PWM_TYPE_CONVENTIONAL) ? true : false; // Configurator feature abused for enabling Fast PWM
- pwm_params.pwmProtocolType = masterConfig.fast_pwm_protocol;
+ pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED); // Configurator feature abused for enabling Fast PWM
+ pwm_params.pwmProtocolType = masterConfig.motor_pwm_protocol;
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;
pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand;
pwm_params.useUnsyncedPwm = masterConfig.use_unsyncedPwm;
if (feature(FEATURE_3D))
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
- if (pwm_params.motorPwmRate > 500 && !pwm_params.useFastPwm)
+ if (masterConfig.motor_pwm_protocol == PWM_TYPE_BRUSHED)
pwm_params.idlePulse = 0; // brushed motors
#ifdef CC3D
pwm_params.useBuzzerP6 = masterConfig.use_buzzer_p6 ? true : false;
@@ -351,6 +351,7 @@ void init(void)
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params);
+ syncMotors(pwm_params.useUnsyncedPwm && pwm_params.motorPwmRate != PWM_TYPE_BRUSHED);
mixerUsePWMOutputConfiguration(pwmOutputConfiguration);
if (!feature(FEATURE_ONESHOT125))
diff --git a/src/main/mw.c b/src/main/mw.c
index 771de46e2..717dc10e8 100644
--- a/src/main/mw.c
+++ b/src/main/mw.c
@@ -742,7 +742,7 @@ void subTaskMotorUpdate(void)
#endif
if (motorControlEnable) {
- writeMotors(masterConfig.fast_pwm_protocol, masterConfig.use_unsyncedPwm);
+ writeMotors();
}
if (debugMode == DEBUG_PIDLOOP) {debug[3] = micros() - startTime;}
}
diff --git a/src/main/scheduler.c b/src/main/scheduler.c
index e4a0ef230..bab23f10e 100755
--- a/src/main/scheduler.c
+++ b/src/main/scheduler.c
@@ -31,6 +31,11 @@
#include "drivers/system.h"
+#if defined (STM32F4)
+#define DELAY_LIMIT 10
+#else
#define DELAY_LIMIT 100
+#endif
+
static cfTask_t *currentTask = NULL;
static uint32_t totalWaitingTasks;
@@ -137,7 +142,7 @@ void rescheduleTask(cfTaskId_e taskId, uint32_t newPeriodMicros)
{
if (taskId == TASK_SELF || taskId < TASK_COUNT) {
cfTask_t *task = taskId == TASK_SELF ? currentTask : &cfTasks[taskId];
- task->desiredPeriod = MAX(100, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging
+ task->desiredPeriod = MAX(DELAY_LIMIT, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging
}
}
diff --git a/src/main/scheduler_tasks.c b/src/main/scheduler_tasks.c
index b9babb4b3..0ab803d2b 100644
--- a/src/main/scheduler_tasks.c
+++ b/src/main/scheduler_tasks.c
@@ -57,7 +57,11 @@ cfTask_t cfTasks[TASK_COUNT] = {
.taskName = "PID",
.subTaskName = "GYRO",
.taskFunc = taskMainPidLoopCheck,
+#if defined(STM32F4)
+ .desiredPeriod = 125,
+#else
.desiredPeriod = 1000,
+#endif
.staticPriority = TASK_PRIORITY_REALTIME,
},
diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h
index 68b0807e5..39a36f074 100644
--- a/src/main/target/ALIENFLIGHTF3/target.h
+++ b/src/main/target/ALIENFLIGHTF3/target.h
@@ -18,6 +18,8 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3.
+#define ALIENFLIGHT
+
#define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PB2
diff --git a/src/main/target/ALIENFLIGHTF4/system_stm32f4xx.c b/src/main/target/ALIENFLIGHTF4/system_stm32f4xx.c
new file mode 100644
index 000000000..33169994a
--- /dev/null
+++ b/src/main/target/ALIENFLIGHTF4/system_stm32f4xx.c
@@ -0,0 +1,1227 @@
+/**
+ ******************************************************************************
+ * @file system_stm32f4xx.c
+ * @author MCD Application Team
+ * @version V1.6.1
+ * @date 21-October-2015
+ * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
+ * This file contains the system clock configuration for STM32F4xx devices.
+ *
+ * 1. This file provides two functions and one global variable to be called from
+ * user application:
+ * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
+ * and Divider factors, AHB/APBx prescalers and Flash settings),
+ * depending on the configuration made in the clock xls tool.
+ * This function is called at startup just after reset and
+ * before branch to main program. This call is made inside
+ * the "startup_stm32f4xx.s" file.
+ *
+ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+ * by the user application to setup the SysTick
+ * timer or configure other parameters.
+ *
+ * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+ * be called whenever the core clock is changed
+ * during program execution.
+ *
+ * 2. After each device reset the HSI (16 MHz) is used as system clock source.
+ * Then SystemInit() function is called, in "startup_stm32f4xx.s" file, to
+ * configure the system clock before to branch to main program.
+ *
+ * 3. If the system clock source selected by user fails to startup, the SystemInit()
+ * function will do nothing and HSI still used as system clock source. User can
+ * add some code to deal with this issue inside the SetSysClock() function.
+ *
+ * 4. The default value of HSE crystal is set to 25MHz, refer to "HSE_VALUE" define
+ * in "stm32f4xx.h" file. When HSE is used as system clock source, directly or
+ * through PLL, and you are using different crystal you have to adapt the HSE
+ * value to your own configuration.
+ *
+ * 5. This file configures the system clock as follows:
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F40xxx/41xxx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 168000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 168000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 4
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 8000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 10
+ *-----------------------------------------------------------------------------
+ * PLL_N | 420
+ *-----------------------------------------------------------------------------
+ * PLL_P | 2
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 5
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F42xxx/43xxx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 4
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 25000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 25
+ *-----------------------------------------------------------------------------
+ * PLL_N | 360
+ *-----------------------------------------------------------------------------
+ * PLL_P | 2
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 5
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F401xx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 84000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 84000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 25000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 25
+ *-----------------------------------------------------------------------------
+ * PLL_N | 336
+ *-----------------------------------------------------------------------------
+ * PLL_P | 4
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 2
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F411xx/STM32F410xx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSI)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 100000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 100000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * HSI Frequency(Hz) | 16000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 16
+ *-----------------------------------------------------------------------------
+ * PLL_N | 400
+ *-----------------------------------------------------------------------------
+ * PLL_P | 4
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 3
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F446xx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 4
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 8000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 8
+ *-----------------------------------------------------------------------------
+ * PLL_N | 360
+ *-----------------------------------------------------------------------------
+ * PLL_P | 2
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLL_R | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_M | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_P | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_Q | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 5
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ ******************************************************************************
+ * @attention
+ *
+ *
© COPYRIGHT 2015 STMicroelectronics
+ *
+ * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+ * You may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at:
+ *
+ * http://www.st.com/software_license_agreement_liberty_v2
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f4xx_system
+ * @{
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Includes
+ * @{
+ */
+
+#include "stm32f4xx.h"
+
+uint32_t hse_value = HSE_VALUE;
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Defines
+ * @{
+ */
+
+/************************* Miscellaneous Configuration ************************/
+/*!< Uncomment the following line if you need to use external SRAM or SDRAM mounted
+ on STM324xG_EVAL/STM324x7I_EVAL/STM324x9I_EVAL boards as data memory */
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx)
+/* #define DATA_IN_ExtSRAM */
+#endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F469_479xx */
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+/* #define DATA_IN_ExtSDRAM */
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F410xx) || defined(STM32F411xE)
+/*!< Uncomment the following line if you need to clock the STM32F410xx/STM32F411xE by HSE Bypass
+ through STLINK MCO pin of STM32F103 microcontroller. The frequency cannot be changed
+ and is fixed at 8 MHz.
+ Hardware configuration needed for Nucleo Board:
+ – SB54, SB55 OFF
+ – R35 removed
+ – SB16, SB50 ON */
+/* #define USE_HSE_BYPASS */
+
+#if defined(USE_HSE_BYPASS)
+#define HSE_BYPASS_INPUT_FREQUENCY 8000000
+#endif /* USE_HSE_BYPASS */
+#endif /* STM32F410xx || STM32F411xE */
+
+/*!< Uncomment the following line if you need to relocate your vector Table in
+ Internal SRAM. */
+/* #define VECT_TAB_SRAM */
+#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
+ This value must be a multiple of 0x200. */
+/******************************************************************************/
+
+/************************* PLL Parameters *************************************/
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx)
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
+ #define PLL_M 8
+#elif defined (STM32F446xx)
+ #define PLL_M 8
+#elif defined (STM32F410xx) || defined (STM32F411xE)
+ #if defined(USE_HSE_BYPASS)
+ #define PLL_M 8
+ #else /* !USE_HSE_BYPASS */
+ #define PLL_M 8
+ #endif /* USE_HSE_BYPASS */
+#else
+#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F469_479xx */
+
+/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
+#define PLL_Q 8
+
+#if defined(STM32F446xx)
+/* PLL division factor for I2S, SAI, SYSTEM and SPDIF: Clock = PLL_VCO / PLLR */
+#define PLL_R 7
+#endif /* STM32F446xx */
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+#define PLL_N 360
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 2
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined (STM32F40_41xxx)
+#define PLL_N 384
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 2
+#endif /* STM32F40_41xxx */
+
+#if defined(STM32F401xx)
+#define PLL_N 336
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 4
+#endif /* STM32F401xx */
+
+#if defined(STM32F410xx) || defined(STM32F411xE)
+#define PLL_N 400
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 4
+#endif /* STM32F410xx || STM32F411xE */
+
+/******************************************************************************/
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Variables
+ * @{
+ */
+
+#if defined(STM32F40_41xxx)
+ uint32_t SystemCoreClock = 192000000;
+#endif /* STM32F40_41xxx */
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ uint32_t SystemCoreClock = 180000000;
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F401xx)
+ uint32_t SystemCoreClock = 84000000;
+#endif /* STM32F401xx */
+
+#if defined(STM32F410xx) || defined(STM32F411xE)
+ uint32_t SystemCoreClock = 100000000;
+#endif /* STM32F410xx || STM32F401xE */
+
+__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_FunctionPrototypes
+ * @{
+ */
+
+void SetSysClock(void);
+
+#if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
+static void SystemInit_ExtMemCtl(void);
+#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system
+ * Initialize the Embedded Flash Interface, the PLL and update the
+ * SystemFrequency variable.
+ * @param None
+ * @retval None
+ */
+void SystemInit(void)
+{
+ /* FPU settings ------------------------------------------------------------*/
+ #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
+ #endif
+ /* Reset the RCC clock configuration to the default reset state ------------*/
+ /* Set HSION bit */
+ RCC->CR |= (uint32_t)0x00000001;
+
+ /* Reset CFGR register */
+ RCC->CFGR = 0x00000000;
+
+ /* Reset HSEON, CSSON and PLLON bits */
+ RCC->CR &= (uint32_t)0xFEF6FFFF;
+
+ /* Reset PLLCFGR register */
+ RCC->PLLCFGR = 0x24003010;
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= (uint32_t)0xFFFBFFFF;
+
+ /* Disable all interrupts */
+ RCC->CIR = 0x00000000;
+
+#if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
+ SystemInit_ExtMemCtl();
+#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
+
+ /* Configure the System clock source, PLL Multiplier and Divider factors,
+ AHB/APBx prescalers and Flash settings ----------------------------------*/
+ SetSysClock();
+
+ /* Configure the Vector Table location add offset address ------------------*/
+#ifdef VECT_TAB_SRAM
+ SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
+#else
+ SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
+#endif
+}
+
+/**
+ * @brief Update SystemCoreClock variable according to Clock Register Values.
+ * The SystemCoreClock variable contains the core clock (HCLK), it can
+ * be used by the user application to setup the SysTick timer or configure
+ * other parameters.
+ *
+ * @note Each time the core clock (HCLK) changes, this function must be called
+ * to update SystemCoreClock variable value. Otherwise, any configuration
+ * based on this variable will be incorrect.
+ *
+ * @note - The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ *
+ * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
+ *
+ * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
+ *
+ * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
+ * or HSI_VALUE(*) multiplied/divided by the PLL factors.
+ *
+ * (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value
+ * 16 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value
+ * 25 MHz), user has to ensure that HSE_VALUE is same as the real
+ * frequency of the crystal used. Otherwise, this function may
+ * have wrong result.
+ *
+ * - The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ *
+ * @param None
+ * @retval None
+ */
+void SystemCoreClockUpdate(void)
+{
+ uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
+#if defined(STM32F446xx)
+ uint32_t pllr = 2;
+#endif /* STM32F446xx */
+ /* Get SYSCLK source -------------------------------------------------------*/
+ tmp = RCC->CFGR & RCC_CFGR_SWS;
+
+ switch (tmp)
+ {
+ case 0x00: /* HSI used as system clock source */
+ SystemCoreClock = HSI_VALUE;
+ break;
+ case 0x04: /* HSE used as system clock source */
+ SystemCoreClock = HSE_VALUE;
+ break;
+ case 0x08: /* PLL P used as system clock source */
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
+ SYSCLK = PLL_VCO / PLL_P
+ */
+ pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
+ pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
+
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+ else
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+#elif defined(STM32F410xx) || defined(STM32F411xE)
+#if defined(USE_HSE_BYPASS)
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_BYPASS_INPUT_FREQUENCY / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+#else
+ if (pllsource == 0)
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+#endif /* USE_HSE_BYPASS */
+#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F446xx || STM32F469_479xx */
+ pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
+ SystemCoreClock = pllvco/pllp;
+ break;
+#if defined(STM32F446xx)
+ case 0x0C: /* PLL R used as system clock source */
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
+ SYSCLK = PLL_VCO / PLL_R
+ */
+ pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
+ pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+ else
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+
+ pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >>28) + 1 ) *2;
+ SystemCoreClock = pllvco/pllr;
+ break;
+#endif /* STM32F446xx */
+ default:
+ SystemCoreClock = HSI_VALUE;
+ break;
+ }
+ /* Compute HCLK frequency --------------------------------------------------*/
+ /* Get HCLK prescaler */
+ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
+ /* HCLK frequency */
+ SystemCoreClock >>= tmp;
+}
+
+/**
+ * @brief Configures the System clock source, PLL Multiplier and Divider factors,
+ * AHB/APBx prescalers and Flash settings
+ * @Note This function should be called only once the RCC clock configuration
+ * is reset to the default reset state (done in SystemInit() function).
+ * @param None
+ * @retval None
+ */
+void SetSysClock(void)
+{
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F446xx)|| defined(STM32F469_479xx)
+/******************************************************************************/
+/* PLL (clocked by HSE) used as System clock source */
+/******************************************************************************/
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* Enable HSE */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+ /* Select regulator voltage output Scale 1 mode */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+ PWR->CR |= PWR_CR_VOS;
+
+ /* HCLK = SYSCLK / 1*/
+ RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
+#endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F401xx)
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+#endif /* STM32F401xx */
+
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx)
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+ (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
+#endif /* STM32F40_41xxx || STM32F401xx || STM32F427_437x || STM32F429_439xx || STM32F469_479xx */
+
+#if defined(STM32F446xx)
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+ (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24) | (PLL_R << 28);
+#endif /* STM32F446xx */
+
+ /* Enable the main PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till the main PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ /* Enable the Over-drive to extend the clock frequency to 180 Mhz */
+ PWR->CR |= PWR_CR_ODEN;
+ while((PWR->CSR & PWR_CSR_ODRDY) == 0)
+ {
+ }
+ PWR->CR |= PWR_CR_ODSWEN;
+ while((PWR->CSR & PWR_CSR_ODSWRDY) == 0)
+ {
+ }
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F40_41xxx)
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
+#endif /* STM32F40_41xxx */
+
+#if defined(STM32F401xx)
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+#endif /* STM32F401xx */
+
+ /* Select the main PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ /* Wait till the main PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+#elif defined(STM32F410xx) || defined(STM32F411xE)
+#if defined(USE_HSE_BYPASS)
+/******************************************************************************/
+/* PLL (clocked by HSE) used as System clock source */
+/******************************************************************************/
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* Enable HSE and HSE BYPASS */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON | RCC_CR_HSEBYP);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+ /* Select regulator voltage output Scale 1 mode */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+ PWR->CR |= PWR_CR_VOS;
+
+ /* HCLK = SYSCLK / 1*/
+ RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+ (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
+
+ /* Enable the main PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till the main PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+
+ /* Select the main PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ /* Wait till the main PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+#else /* HSI will be used as PLL clock source */
+ /* Select regulator voltage output Scale 1 mode */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+ PWR->CR |= PWR_CR_VOS;
+
+ /* HCLK = SYSCLK / 1*/
+ RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) | (PLL_Q << 24);
+
+ /* Enable the main PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till the main PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+
+ /* Select the main PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ /* Wait till the main PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+ {
+ }
+#endif /* USE_HSE_BYPASS */
+#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F469_479xx */
+}
+
+/**
+ * @brief Setup the external memory controller. Called in startup_stm32f4xx.s
+ * before jump to __main
+ * @param None
+ * @retval None
+ */
+#ifdef DATA_IN_ExtSRAM
+/**
+ * @brief Setup the external memory controller.
+ * Called in startup_stm32f4xx.s before jump to main.
+ * This function configures the external SRAM mounted on STM324xG_EVAL/STM324x7I boards
+ * This SRAM will be used as program data memory (including heap and stack).
+ * @param None
+ * @retval None
+ */
+void SystemInit_ExtMemCtl(void)
+{
+/*-- GPIOs Configuration -----------------------------------------------------*/
+/*
+ +-------------------+--------------------+------------------+--------------+
+ + SRAM pins assignment +
+ +-------------------+--------------------+------------------+--------------+
+ | PD0 <-> FMC_D2 | PE0 <-> FMC_NBL0 | PF0 <-> FMC_A0 | PG0 <-> FMC_A10 |
+ | PD1 <-> FMC_D3 | PE1 <-> FMC_NBL1 | PF1 <-> FMC_A1 | PG1 <-> FMC_A11 |
+ | PD4 <-> FMC_NOE | PE3 <-> FMC_A19 | PF2 <-> FMC_A2 | PG2 <-> FMC_A12 |
+ | PD5 <-> FMC_NWE | PE4 <-> FMC_A20 | PF3 <-> FMC_A3 | PG3 <-> FMC_A13 |
+ | PD8 <-> FMC_D13 | PE7 <-> FMC_D4 | PF4 <-> FMC_A4 | PG4 <-> FMC_A14 |
+ | PD9 <-> FMC_D14 | PE8 <-> FMC_D5 | PF5 <-> FMC_A5 | PG5 <-> FMC_A15 |
+ | PD10 <-> FMC_D15 | PE9 <-> FMC_D6 | PF12 <-> FMC_A6 | PG9 <-> FMC_NE2 |
+ | PD11 <-> FMC_A16 | PE10 <-> FMC_D7 | PF13 <-> FMC_A7 |-----------------+
+ | PD12 <-> FMC_A17 | PE11 <-> FMC_D8 | PF14 <-> FMC_A8 |
+ | PD13 <-> FMC_A18 | PE12 <-> FMC_D9 | PF15 <-> FMC_A9 |
+ | PD14 <-> FMC_D0 | PE13 <-> FMC_D10 |-----------------+
+ | PD15 <-> FMC_D1 | PE14 <-> FMC_D11 |
+ | | PE15 <-> FMC_D12 |
+ +------------------+------------------+
+*/
+ /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
+ RCC->AHB1ENR |= 0x00000078;
+
+ /* Connect PDx pins to FMC Alternate function */
+ GPIOD->AFR[0] = 0x00cc00cc;
+ GPIOD->AFR[1] = 0xcccccccc;
+ /* Configure PDx pins in Alternate function mode */
+ GPIOD->MODER = 0xaaaa0a0a;
+ /* Configure PDx pins speed to 100 MHz */
+ GPIOD->OSPEEDR = 0xffff0f0f;
+ /* Configure PDx pins Output type to push-pull */
+ GPIOD->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PDx pins */
+ GPIOD->PUPDR = 0x00000000;
+
+ /* Connect PEx pins to FMC Alternate function */
+ GPIOE->AFR[0] = 0xcccccccc;
+ GPIOE->AFR[1] = 0xcccccccc;
+ /* Configure PEx pins in Alternate function mode */
+ GPIOE->MODER = 0xaaaaaaaa;
+ /* Configure PEx pins speed to 100 MHz */
+ GPIOE->OSPEEDR = 0xffffffff;
+ /* Configure PEx pins Output type to push-pull */
+ GPIOE->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PEx pins */
+ GPIOE->PUPDR = 0x00000000;
+
+ /* Connect PFx pins to FMC Alternate function */
+ GPIOF->AFR[0] = 0x00cccccc;
+ GPIOF->AFR[1] = 0xcccc0000;
+ /* Configure PFx pins in Alternate function mode */
+ GPIOF->MODER = 0xaa000aaa;
+ /* Configure PFx pins speed to 100 MHz */
+ GPIOF->OSPEEDR = 0xff000fff;
+ /* Configure PFx pins Output type to push-pull */
+ GPIOF->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PFx pins */
+ GPIOF->PUPDR = 0x00000000;
+
+ /* Connect PGx pins to FMC Alternate function */
+ GPIOG->AFR[0] = 0x00cccccc;
+ GPIOG->AFR[1] = 0x000000c0;
+ /* Configure PGx pins in Alternate function mode */
+ GPIOG->MODER = 0x00080aaa;
+ /* Configure PGx pins speed to 100 MHz */
+ GPIOG->OSPEEDR = 0x000c0fff;
+ /* Configure PGx pins Output type to push-pull */
+ GPIOG->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PGx pins */
+ GPIOG->PUPDR = 0x00000000;
+
+/*-- FMC Configuration ------------------------------------------------------*/
+ /* Enable the FMC/FSMC interface clock */
+ RCC->AHB3ENR |= 0x00000001;
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ /* Configure and enable Bank1_SRAM2 */
+ FMC_Bank1->BTCR[2] = 0x00001011;
+ FMC_Bank1->BTCR[3] = 0x00000201;
+ FMC_Bank1E->BWTR[2] = 0x0fffffff;
+#endif /* STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F40_41xxx)
+ /* Configure and enable Bank1_SRAM2 */
+ FSMC_Bank1->BTCR[2] = 0x00001011;
+ FSMC_Bank1->BTCR[3] = 0x00000201;
+ FSMC_Bank1E->BWTR[2] = 0x0fffffff;
+#endif /* STM32F40_41xxx */
+
+/*
+ Bank1_SRAM2 is configured as follow:
+ In case of FSMC configuration
+ NORSRAMTimingStructure.FSMC_AddressSetupTime = 1;
+ NORSRAMTimingStructure.FSMC_AddressHoldTime = 0;
+ NORSRAMTimingStructure.FSMC_DataSetupTime = 2;
+ NORSRAMTimingStructure.FSMC_BusTurnAroundDuration = 0;
+ NORSRAMTimingStructure.FSMC_CLKDivision = 0;
+ NORSRAMTimingStructure.FSMC_DataLatency = 0;
+ NORSRAMTimingStructure.FSMC_AccessMode = FMC_AccessMode_A;
+
+ FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2;
+ FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_SRAM;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
+ FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+ FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+ FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
+ FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &NORSRAMTimingStructure;
+
+ In case of FMC configuration
+ NORSRAMTimingStructure.FMC_AddressSetupTime = 1;
+ NORSRAMTimingStructure.FMC_AddressHoldTime = 0;
+ NORSRAMTimingStructure.FMC_DataSetupTime = 2;
+ NORSRAMTimingStructure.FMC_BusTurnAroundDuration = 0;
+ NORSRAMTimingStructure.FMC_CLKDivision = 0;
+ NORSRAMTimingStructure.FMC_DataLatency = 0;
+ NORSRAMTimingStructure.FMC_AccessMode = FMC_AccessMode_A;
+
+ FMC_NORSRAMInitStructure.FMC_Bank = FMC_Bank1_NORSRAM2;
+ FMC_NORSRAMInitStructure.FMC_DataAddressMux = FMC_DataAddressMux_Disable;
+ FMC_NORSRAMInitStructure.FMC_MemoryType = FMC_MemoryType_SRAM;
+ FMC_NORSRAMInitStructure.FMC_MemoryDataWidth = FMC_MemoryDataWidth_16b;
+ FMC_NORSRAMInitStructure.FMC_BurstAccessMode = FMC_BurstAccessMode_Disable;
+ FMC_NORSRAMInitStructure.FMC_AsynchronousWait = FMC_AsynchronousWait_Disable;
+ FMC_NORSRAMInitStructure.FMC_WaitSignalPolarity = FMC_WaitSignalPolarity_Low;
+ FMC_NORSRAMInitStructure.FMC_WrapMode = FMC_WrapMode_Disable;
+ FMC_NORSRAMInitStructure.FMC_WaitSignalActive = FMC_WaitSignalActive_BeforeWaitState;
+ FMC_NORSRAMInitStructure.FMC_WriteOperation = FMC_WriteOperation_Enable;
+ FMC_NORSRAMInitStructure.FMC_WaitSignal = FMC_WaitSignal_Disable;
+ FMC_NORSRAMInitStructure.FMC_ExtendedMode = FMC_ExtendedMode_Disable;
+ FMC_NORSRAMInitStructure.FMC_WriteBurst = FMC_WriteBurst_Disable;
+ FMC_NORSRAMInitStructure.FMC_ContinousClock = FMC_CClock_SyncOnly;
+ FMC_NORSRAMInitStructure.FMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
+ FMC_NORSRAMInitStructure.FMC_WriteTimingStruct = &NORSRAMTimingStructure;
+*/
+
+}
+#endif /* DATA_IN_ExtSRAM */
+
+#ifdef DATA_IN_ExtSDRAM
+/**
+ * @brief Setup the external memory controller.
+ * Called in startup_stm32f4xx.s before jump to main.
+ * This function configures the external SDRAM mounted on STM324x9I_EVAL board
+ * This SDRAM will be used as program data memory (including heap and stack).
+ * @param None
+ * @retval None
+ */
+void SystemInit_ExtMemCtl(void)
+{
+ register uint32_t tmpreg = 0, timeout = 0xFFFF;
+ register uint32_t index;
+
+ /* Enable GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface
+ clock */
+ RCC->AHB1ENR |= 0x000001FC;
+
+ /* Connect PCx pins to FMC Alternate function */
+ GPIOC->AFR[0] = 0x0000000c;
+ GPIOC->AFR[1] = 0x00007700;
+ /* Configure PCx pins in Alternate function mode */
+ GPIOC->MODER = 0x00a00002;
+ /* Configure PCx pins speed to 50 MHz */
+ GPIOC->OSPEEDR = 0x00a00002;
+ /* Configure PCx pins Output type to push-pull */
+ GPIOC->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PCx pins */
+ GPIOC->PUPDR = 0x00500000;
+
+ /* Connect PDx pins to FMC Alternate function */
+ GPIOD->AFR[0] = 0x000000CC;
+ GPIOD->AFR[1] = 0xCC000CCC;
+ /* Configure PDx pins in Alternate function mode */
+ GPIOD->MODER = 0xA02A000A;
+ /* Configure PDx pins speed to 50 MHz */
+ GPIOD->OSPEEDR = 0xA02A000A;
+ /* Configure PDx pins Output type to push-pull */
+ GPIOD->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PDx pins */
+ GPIOD->PUPDR = 0x00000000;
+
+ /* Connect PEx pins to FMC Alternate function */
+ GPIOE->AFR[0] = 0xC00000CC;
+ GPIOE->AFR[1] = 0xCCCCCCCC;
+ /* Configure PEx pins in Alternate function mode */
+ GPIOE->MODER = 0xAAAA800A;
+ /* Configure PEx pins speed to 50 MHz */
+ GPIOE->OSPEEDR = 0xAAAA800A;
+ /* Configure PEx pins Output type to push-pull */
+ GPIOE->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PEx pins */
+ GPIOE->PUPDR = 0x00000000;
+
+ /* Connect PFx pins to FMC Alternate function */
+ GPIOF->AFR[0] = 0xcccccccc;
+ GPIOF->AFR[1] = 0xcccccccc;
+ /* Configure PFx pins in Alternate function mode */
+ GPIOF->MODER = 0xAA800AAA;
+ /* Configure PFx pins speed to 50 MHz */
+ GPIOF->OSPEEDR = 0xAA800AAA;
+ /* Configure PFx pins Output type to push-pull */
+ GPIOF->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PFx pins */
+ GPIOF->PUPDR = 0x00000000;
+
+ /* Connect PGx pins to FMC Alternate function */
+ GPIOG->AFR[0] = 0xcccccccc;
+ GPIOG->AFR[1] = 0xcccccccc;
+ /* Configure PGx pins in Alternate function mode */
+ GPIOG->MODER = 0xaaaaaaaa;
+ /* Configure PGx pins speed to 50 MHz */
+ GPIOG->OSPEEDR = 0xaaaaaaaa;
+ /* Configure PGx pins Output type to push-pull */
+ GPIOG->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PGx pins */
+ GPIOG->PUPDR = 0x00000000;
+
+ /* Connect PHx pins to FMC Alternate function */
+ GPIOH->AFR[0] = 0x00C0CC00;
+ GPIOH->AFR[1] = 0xCCCCCCCC;
+ /* Configure PHx pins in Alternate function mode */
+ GPIOH->MODER = 0xAAAA08A0;
+ /* Configure PHx pins speed to 50 MHz */
+ GPIOH->OSPEEDR = 0xAAAA08A0;
+ /* Configure PHx pins Output type to push-pull */
+ GPIOH->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PHx pins */
+ GPIOH->PUPDR = 0x00000000;
+
+ /* Connect PIx pins to FMC Alternate function */
+ GPIOI->AFR[0] = 0xCCCCCCCC;
+ GPIOI->AFR[1] = 0x00000CC0;
+ /* Configure PIx pins in Alternate function mode */
+ GPIOI->MODER = 0x0028AAAA;
+ /* Configure PIx pins speed to 50 MHz */
+ GPIOI->OSPEEDR = 0x0028AAAA;
+ /* Configure PIx pins Output type to push-pull */
+ GPIOI->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PIx pins */
+ GPIOI->PUPDR = 0x00000000;
+
+/*-- FMC Configuration ------------------------------------------------------*/
+ /* Enable the FMC interface clock */
+ RCC->AHB3ENR |= 0x00000001;
+
+ /* Configure and enable SDRAM bank1 */
+ FMC_Bank5_6->SDCR[0] = 0x000039D0;
+ FMC_Bank5_6->SDTR[0] = 0x01115351;
+
+ /* SDRAM initialization sequence */
+ /* Clock enable command */
+ FMC_Bank5_6->SDCMR = 0x00000011;
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Delay */
+ for (index = 0; index<1000; index++);
+
+ /* PALL command */
+ FMC_Bank5_6->SDCMR = 0x00000012;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Auto refresh command */
+ FMC_Bank5_6->SDCMR = 0x00000073;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* MRD register program */
+ FMC_Bank5_6->SDCMR = 0x00046014;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Set refresh count */
+ tmpreg = FMC_Bank5_6->SDRTR;
+ FMC_Bank5_6->SDRTR = (tmpreg | (0x0000027C<<1));
+
+ /* Disable write protection */
+ tmpreg = FMC_Bank5_6->SDCR[0];
+ FMC_Bank5_6->SDCR[0] = (tmpreg & 0xFFFFFDFF);
+
+/*
+ Bank1_SDRAM is configured as follow:
+
+ FMC_SDRAMTimingInitStructure.FMC_LoadToActiveDelay = 2;
+ FMC_SDRAMTimingInitStructure.FMC_ExitSelfRefreshDelay = 6;
+ FMC_SDRAMTimingInitStructure.FMC_SelfRefreshTime = 4;
+ FMC_SDRAMTimingInitStructure.FMC_RowCycleDelay = 6;
+ FMC_SDRAMTimingInitStructure.FMC_WriteRecoveryTime = 2;
+ FMC_SDRAMTimingInitStructure.FMC_RPDelay = 2;
+ FMC_SDRAMTimingInitStructure.FMC_RCDDelay = 2;
+
+ FMC_SDRAMInitStructure.FMC_Bank = SDRAM_BANK;
+ FMC_SDRAMInitStructure.FMC_ColumnBitsNumber = FMC_ColumnBits_Number_8b;
+ FMC_SDRAMInitStructure.FMC_RowBitsNumber = FMC_RowBits_Number_11b;
+ FMC_SDRAMInitStructure.FMC_SDMemoryDataWidth = FMC_SDMemory_Width_16b;
+ FMC_SDRAMInitStructure.FMC_InternalBankNumber = FMC_InternalBank_Number_4;
+ FMC_SDRAMInitStructure.FMC_CASLatency = FMC_CAS_Latency_3;
+ FMC_SDRAMInitStructure.FMC_WriteProtection = FMC_Write_Protection_Disable;
+ FMC_SDRAMInitStructure.FMC_SDClockPeriod = FMC_SDClock_Period_2;
+ FMC_SDRAMInitStructure.FMC_ReadBurst = FMC_Read_Burst_disable;
+ FMC_SDRAMInitStructure.FMC_ReadPipeDelay = FMC_ReadPipe_Delay_1;
+ FMC_SDRAMInitStructure.FMC_SDRAMTimingStruct = &FMC_SDRAMTimingInitStructure;
+*/
+
+}
+#endif /* DATA_IN_ExtSDRAM */
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/src/main/target/ALIENFLIGHTF4/system_stm32f4xx.h b/src/main/target/ALIENFLIGHTF4/system_stm32f4xx.h
new file mode 100644
index 000000000..5e30ef818
--- /dev/null
+++ b/src/main/target/ALIENFLIGHTF4/system_stm32f4xx.h
@@ -0,0 +1,105 @@
+/**
+ ******************************************************************************
+ * @file system_stm32f4xx.h
+ * @author MCD Application Team
+ * @version V1.6.1
+ * @date 21-October-2015
+ * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT 2015 STMicroelectronics
+ *
+ * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+ * You may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at:
+ *
+ * http://www.st.com/software_license_agreement_liberty_v2
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f4xx_system
+ * @{
+ */
+
+/**
+ * @brief Define to prevent recursive inclusion
+ */
+#ifndef __SYSTEM_STM32F4XX_H
+#define __SYSTEM_STM32F4XX_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/** @addtogroup STM32F4xx_System_Includes
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @addtogroup STM32F4xx_System_Exported_types
+ * @{
+ */
+
+extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
+
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Exported_Constants
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Exported_Functions
+ * @{
+ */
+
+extern void SystemInit(void);
+extern void SystemCoreClockUpdate(void);
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__SYSTEM_STM32F4XX_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h
index 00107e674..c71c278d1 100644
--- a/src/main/target/ALIENFLIGHTF4/target.h
+++ b/src/main/target/ALIENFLIGHTF4/target.h
@@ -17,6 +17,7 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "AFF4"
+#define ALIENFLIGHT
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define CONFIG_SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
@@ -50,7 +51,7 @@
#define ACC
#define USE_ACC_SPI_MPU6500
-//#define USE_ACC_SPI_MPU9250
+#define USE_ACC_SPI_MPU9250
#define ACC_MPU6500_ALIGN CW270_DEG
#define ACC_MPU9250_ALIGN CW270_DEG
diff --git a/src/main/target/BLUEJAYF4/system_stm32f4xx.c b/src/main/target/BLUEJAYF4/system_stm32f4xx.c
new file mode 100644
index 000000000..805859fb2
--- /dev/null
+++ b/src/main/target/BLUEJAYF4/system_stm32f4xx.c
@@ -0,0 +1,1227 @@
+/**
+ ******************************************************************************
+ * @file system_stm32f4xx.c
+ * @author MCD Application Team
+ * @version V1.6.1
+ * @date 21-October-2015
+ * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
+ * This file contains the system clock configuration for STM32F4xx devices.
+ *
+ * 1. This file provides two functions and one global variable to be called from
+ * user application:
+ * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
+ * and Divider factors, AHB/APBx prescalers and Flash settings),
+ * depending on the configuration made in the clock xls tool.
+ * This function is called at startup just after reset and
+ * before branch to main program. This call is made inside
+ * the "startup_stm32f4xx.s" file.
+ *
+ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+ * by the user application to setup the SysTick
+ * timer or configure other parameters.
+ *
+ * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+ * be called whenever the core clock is changed
+ * during program execution.
+ *
+ * 2. After each device reset the HSI (16 MHz) is used as system clock source.
+ * Then SystemInit() function is called, in "startup_stm32f4xx.s" file, to
+ * configure the system clock before to branch to main program.
+ *
+ * 3. If the system clock source selected by user fails to startup, the SystemInit()
+ * function will do nothing and HSI still used as system clock source. User can
+ * add some code to deal with this issue inside the SetSysClock() function.
+ *
+ * 4. The default value of HSE crystal is set to 25MHz, refer to "HSE_VALUE" define
+ * in "stm32f4xx.h" file. When HSE is used as system clock source, directly or
+ * through PLL, and you are using different crystal you have to adapt the HSE
+ * value to your own configuration.
+ *
+ * 5. This file configures the system clock as follows:
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F40xxx/41xxx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 168000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 168000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 4
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 8000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 10
+ *-----------------------------------------------------------------------------
+ * PLL_N | 420
+ *-----------------------------------------------------------------------------
+ * PLL_P | 2
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 5
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F42xxx/43xxx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 4
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 25000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 25
+ *-----------------------------------------------------------------------------
+ * PLL_N | 360
+ *-----------------------------------------------------------------------------
+ * PLL_P | 2
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 5
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F401xx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 84000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 84000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 25000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 25
+ *-----------------------------------------------------------------------------
+ * PLL_N | 336
+ *-----------------------------------------------------------------------------
+ * PLL_P | 4
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 2
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F411xx/STM32F410xx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSI)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 100000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 100000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * HSI Frequency(Hz) | 16000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 16
+ *-----------------------------------------------------------------------------
+ * PLL_N | 400
+ *-----------------------------------------------------------------------------
+ * PLL_P | 4
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 3
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F446xx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 4
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 8000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 8
+ *-----------------------------------------------------------------------------
+ * PLL_N | 360
+ *-----------------------------------------------------------------------------
+ * PLL_P | 2
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLL_R | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_M | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_P | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_Q | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 5
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT 2015 STMicroelectronics
+ *
+ * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+ * You may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at:
+ *
+ * http://www.st.com/software_license_agreement_liberty_v2
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f4xx_system
+ * @{
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Includes
+ * @{
+ */
+
+#include "stm32f4xx.h"
+
+uint32_t hse_value = HSE_VALUE;
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Defines
+ * @{
+ */
+
+/************************* Miscellaneous Configuration ************************/
+/*!< Uncomment the following line if you need to use external SRAM or SDRAM mounted
+ on STM324xG_EVAL/STM324x7I_EVAL/STM324x9I_EVAL boards as data memory */
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx)
+/* #define DATA_IN_ExtSRAM */
+#endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F469_479xx */
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+/* #define DATA_IN_ExtSDRAM */
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F410xx) || defined(STM32F411xE)
+/*!< Uncomment the following line if you need to clock the STM32F410xx/STM32F411xE by HSE Bypass
+ through STLINK MCO pin of STM32F103 microcontroller. The frequency cannot be changed
+ and is fixed at 8 MHz.
+ Hardware configuration needed for Nucleo Board:
+ – SB54, SB55 OFF
+ – R35 removed
+ – SB16, SB50 ON */
+/* #define USE_HSE_BYPASS */
+
+#if defined(USE_HSE_BYPASS)
+#define HSE_BYPASS_INPUT_FREQUENCY 8000000
+#endif /* USE_HSE_BYPASS */
+#endif /* STM32F410xx || STM32F411xE */
+
+/*!< Uncomment the following line if you need to relocate your vector Table in
+ Internal SRAM. */
+/* #define VECT_TAB_SRAM */
+#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
+ This value must be a multiple of 0x200. */
+/******************************************************************************/
+
+/************************* PLL Parameters *************************************/
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx)
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
+ #define PLL_M 8
+#elif defined (STM32F446xx)
+ #define PLL_M 8
+#elif defined (STM32F410xx) || defined (STM32F411xE)
+ #if defined(USE_HSE_BYPASS)
+ #define PLL_M 8
+ #else /* !USE_HSE_BYPASS */
+ #define PLL_M 8
+ #endif /* USE_HSE_BYPASS */
+#else
+#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F469_479xx */
+
+/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
+#define PLL_Q 8
+
+#if defined(STM32F446xx)
+/* PLL division factor for I2S, SAI, SYSTEM and SPDIF: Clock = PLL_VCO / PLLR */
+#define PLL_R 7
+#endif /* STM32F446xx */
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+#define PLL_N 360
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 2
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined (STM32F40_41xxx)
+#define PLL_N 384
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 2
+#endif /* STM32F40_41xxx */
+
+#if defined(STM32F401xx)
+#define PLL_N 336
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 4
+#endif /* STM32F401xx */
+
+#if defined(STM32F410xx) || defined(STM32F411xE)
+#define PLL_N 400
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 4
+#endif /* STM32F410xx || STM32F411xE */
+
+/******************************************************************************/
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Variables
+ * @{
+ */
+
+#if defined(STM32F40_41xxx)
+ uint32_t SystemCoreClock = 192000000;
+#endif /* STM32F40_41xxx */
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ uint32_t SystemCoreClock = 180000000;
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F401xx)
+ uint32_t SystemCoreClock = 84000000;
+#endif /* STM32F401xx */
+
+#if defined(STM32F410xx) || defined(STM32F411xE)
+ uint32_t SystemCoreClock = 100000000;
+#endif /* STM32F410xx || STM32F401xE */
+
+__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_FunctionPrototypes
+ * @{
+ */
+
+void SetSysClock(void);
+
+#if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
+static void SystemInit_ExtMemCtl(void);
+#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system
+ * Initialize the Embedded Flash Interface, the PLL and update the
+ * SystemFrequency variable.
+ * @param None
+ * @retval None
+ */
+void SystemInit(void)
+{
+ /* FPU settings ------------------------------------------------------------*/
+ #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
+ #endif
+ /* Reset the RCC clock configuration to the default reset state ------------*/
+ /* Set HSION bit */
+ RCC->CR |= (uint32_t)0x00000001;
+
+ /* Reset CFGR register */
+ RCC->CFGR = 0x00000000;
+
+ /* Reset HSEON, CSSON and PLLON bits */
+ RCC->CR &= (uint32_t)0xFEF6FFFF;
+
+ /* Reset PLLCFGR register */
+ RCC->PLLCFGR = 0x24003010;
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= (uint32_t)0xFFFBFFFF;
+
+ /* Disable all interrupts */
+ RCC->CIR = 0x00000000;
+
+#if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
+ SystemInit_ExtMemCtl();
+#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
+
+ /* Configure the System clock source, PLL Multiplier and Divider factors,
+ AHB/APBx prescalers and Flash settings ----------------------------------*/
+ SetSysClock();
+
+ /* Configure the Vector Table location add offset address ------------------*/
+#ifdef VECT_TAB_SRAM
+ SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
+#else
+ SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
+#endif
+}
+
+/**
+ * @brief Update SystemCoreClock variable according to Clock Register Values.
+ * The SystemCoreClock variable contains the core clock (HCLK), it can
+ * be used by the user application to setup the SysTick timer or configure
+ * other parameters.
+ *
+ * @note Each time the core clock (HCLK) changes, this function must be called
+ * to update SystemCoreClock variable value. Otherwise, any configuration
+ * based on this variable will be incorrect.
+ *
+ * @note - The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ *
+ * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
+ *
+ * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
+ *
+ * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
+ * or HSI_VALUE(*) multiplied/divided by the PLL factors.
+ *
+ * (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value
+ * 16 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value
+ * 25 MHz), user has to ensure that HSE_VALUE is same as the real
+ * frequency of the crystal used. Otherwise, this function may
+ * have wrong result.
+ *
+ * - The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ *
+ * @param None
+ * @retval None
+ */
+void SystemCoreClockUpdate(void)
+{
+ uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
+#if defined(STM32F446xx)
+ uint32_t pllr = 2;
+#endif /* STM32F446xx */
+ /* Get SYSCLK source -------------------------------------------------------*/
+ tmp = RCC->CFGR & RCC_CFGR_SWS;
+
+ switch (tmp)
+ {
+ case 0x00: /* HSI used as system clock source */
+ SystemCoreClock = HSI_VALUE;
+ break;
+ case 0x04: /* HSE used as system clock source */
+ SystemCoreClock = HSE_VALUE;
+ break;
+ case 0x08: /* PLL P used as system clock source */
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
+ SYSCLK = PLL_VCO / PLL_P
+ */
+ pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
+ pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
+
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+ else
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+#elif defined(STM32F410xx) || defined(STM32F411xE)
+#if defined(USE_HSE_BYPASS)
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_BYPASS_INPUT_FREQUENCY / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+#else
+ if (pllsource == 0)
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+#endif /* USE_HSE_BYPASS */
+#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F446xx || STM32F469_479xx */
+ pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
+ SystemCoreClock = pllvco/pllp;
+ break;
+#if defined(STM32F446xx)
+ case 0x0C: /* PLL R used as system clock source */
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
+ SYSCLK = PLL_VCO / PLL_R
+ */
+ pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
+ pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+ else
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+
+ pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >>28) + 1 ) *2;
+ SystemCoreClock = pllvco/pllr;
+ break;
+#endif /* STM32F446xx */
+ default:
+ SystemCoreClock = HSI_VALUE;
+ break;
+ }
+ /* Compute HCLK frequency --------------------------------------------------*/
+ /* Get HCLK prescaler */
+ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
+ /* HCLK frequency */
+ SystemCoreClock >>= tmp;
+}
+
+/**
+ * @brief Configures the System clock source, PLL Multiplier and Divider factors,
+ * AHB/APBx prescalers and Flash settings
+ * @Note This function should be called only once the RCC clock configuration
+ * is reset to the default reset state (done in SystemInit() function).
+ * @param None
+ * @retval None
+ */
+void SetSysClock(void)
+{
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F446xx)|| defined(STM32F469_479xx)
+/******************************************************************************/
+/* PLL (clocked by HSE) used as System clock source */
+/******************************************************************************/
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* Enable HSE */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+ /* Select regulator voltage output Scale 1 mode */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+ PWR->CR |= PWR_CR_VOS;
+
+ /* HCLK = SYSCLK / 1*/
+ RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
+#endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F401xx)
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+#endif /* STM32F401xx */
+
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx)
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+ (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
+#endif /* STM32F40_41xxx || STM32F401xx || STM32F427_437x || STM32F429_439xx || STM32F469_479xx */
+
+#if defined(STM32F446xx)
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+ (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24) | (PLL_R << 28);
+#endif /* STM32F446xx */
+
+ /* Enable the main PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till the main PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ /* Enable the Over-drive to extend the clock frequency to 180 Mhz */
+ PWR->CR |= PWR_CR_ODEN;
+ while((PWR->CSR & PWR_CSR_ODRDY) == 0)
+ {
+ }
+ PWR->CR |= PWR_CR_ODSWEN;
+ while((PWR->CSR & PWR_CSR_ODSWRDY) == 0)
+ {
+ }
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F40_41xxx)
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
+#endif /* STM32F40_41xxx */
+
+#if defined(STM32F401xx)
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+#endif /* STM32F401xx */
+
+ /* Select the main PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ /* Wait till the main PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+#elif defined(STM32F410xx) || defined(STM32F411xE)
+#if defined(USE_HSE_BYPASS)
+/******************************************************************************/
+/* PLL (clocked by HSE) used as System clock source */
+/******************************************************************************/
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* Enable HSE and HSE BYPASS */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON | RCC_CR_HSEBYP);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+ /* Select regulator voltage output Scale 1 mode */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+ PWR->CR |= PWR_CR_VOS;
+
+ /* HCLK = SYSCLK / 1*/
+ RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+ (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
+
+ /* Enable the main PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till the main PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+
+ /* Select the main PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ /* Wait till the main PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+#else /* HSI will be used as PLL clock source */
+ /* Select regulator voltage output Scale 1 mode */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+ PWR->CR |= PWR_CR_VOS;
+
+ /* HCLK = SYSCLK / 1*/
+ RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) | (PLL_Q << 24);
+
+ /* Enable the main PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till the main PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+
+ /* Select the main PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ /* Wait till the main PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+ {
+ }
+#endif /* USE_HSE_BYPASS */
+#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F469_479xx */
+}
+
+/**
+ * @brief Setup the external memory controller. Called in startup_stm32f4xx.s
+ * before jump to __main
+ * @param None
+ * @retval None
+ */
+#ifdef DATA_IN_ExtSRAM
+/**
+ * @brief Setup the external memory controller.
+ * Called in startup_stm32f4xx.s before jump to main.
+ * This function configures the external SRAM mounted on STM324xG_EVAL/STM324x7I boards
+ * This SRAM will be used as program data memory (including heap and stack).
+ * @param None
+ * @retval None
+ */
+void SystemInit_ExtMemCtl(void)
+{
+/*-- GPIOs Configuration -----------------------------------------------------*/
+/*
+ +-------------------+--------------------+------------------+--------------+
+ + SRAM pins assignment +
+ +-------------------+--------------------+------------------+--------------+
+ | PD0 <-> FMC_D2 | PE0 <-> FMC_NBL0 | PF0 <-> FMC_A0 | PG0 <-> FMC_A10 |
+ | PD1 <-> FMC_D3 | PE1 <-> FMC_NBL1 | PF1 <-> FMC_A1 | PG1 <-> FMC_A11 |
+ | PD4 <-> FMC_NOE | PE3 <-> FMC_A19 | PF2 <-> FMC_A2 | PG2 <-> FMC_A12 |
+ | PD5 <-> FMC_NWE | PE4 <-> FMC_A20 | PF3 <-> FMC_A3 | PG3 <-> FMC_A13 |
+ | PD8 <-> FMC_D13 | PE7 <-> FMC_D4 | PF4 <-> FMC_A4 | PG4 <-> FMC_A14 |
+ | PD9 <-> FMC_D14 | PE8 <-> FMC_D5 | PF5 <-> FMC_A5 | PG5 <-> FMC_A15 |
+ | PD10 <-> FMC_D15 | PE9 <-> FMC_D6 | PF12 <-> FMC_A6 | PG9 <-> FMC_NE2 |
+ | PD11 <-> FMC_A16 | PE10 <-> FMC_D7 | PF13 <-> FMC_A7 |-----------------+
+ | PD12 <-> FMC_A17 | PE11 <-> FMC_D8 | PF14 <-> FMC_A8 |
+ | PD13 <-> FMC_A18 | PE12 <-> FMC_D9 | PF15 <-> FMC_A9 |
+ | PD14 <-> FMC_D0 | PE13 <-> FMC_D10 |-----------------+
+ | PD15 <-> FMC_D1 | PE14 <-> FMC_D11 |
+ | | PE15 <-> FMC_D12 |
+ +------------------+------------------+
+*/
+ /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
+ RCC->AHB1ENR |= 0x00000078;
+
+ /* Connect PDx pins to FMC Alternate function */
+ GPIOD->AFR[0] = 0x00cc00cc;
+ GPIOD->AFR[1] = 0xcccccccc;
+ /* Configure PDx pins in Alternate function mode */
+ GPIOD->MODER = 0xaaaa0a0a;
+ /* Configure PDx pins speed to 100 MHz */
+ GPIOD->OSPEEDR = 0xffff0f0f;
+ /* Configure PDx pins Output type to push-pull */
+ GPIOD->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PDx pins */
+ GPIOD->PUPDR = 0x00000000;
+
+ /* Connect PEx pins to FMC Alternate function */
+ GPIOE->AFR[0] = 0xcccccccc;
+ GPIOE->AFR[1] = 0xcccccccc;
+ /* Configure PEx pins in Alternate function mode */
+ GPIOE->MODER = 0xaaaaaaaa;
+ /* Configure PEx pins speed to 100 MHz */
+ GPIOE->OSPEEDR = 0xffffffff;
+ /* Configure PEx pins Output type to push-pull */
+ GPIOE->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PEx pins */
+ GPIOE->PUPDR = 0x00000000;
+
+ /* Connect PFx pins to FMC Alternate function */
+ GPIOF->AFR[0] = 0x00cccccc;
+ GPIOF->AFR[1] = 0xcccc0000;
+ /* Configure PFx pins in Alternate function mode */
+ GPIOF->MODER = 0xaa000aaa;
+ /* Configure PFx pins speed to 100 MHz */
+ GPIOF->OSPEEDR = 0xff000fff;
+ /* Configure PFx pins Output type to push-pull */
+ GPIOF->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PFx pins */
+ GPIOF->PUPDR = 0x00000000;
+
+ /* Connect PGx pins to FMC Alternate function */
+ GPIOG->AFR[0] = 0x00cccccc;
+ GPIOG->AFR[1] = 0x000000c0;
+ /* Configure PGx pins in Alternate function mode */
+ GPIOG->MODER = 0x00080aaa;
+ /* Configure PGx pins speed to 100 MHz */
+ GPIOG->OSPEEDR = 0x000c0fff;
+ /* Configure PGx pins Output type to push-pull */
+ GPIOG->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PGx pins */
+ GPIOG->PUPDR = 0x00000000;
+
+/*-- FMC Configuration ------------------------------------------------------*/
+ /* Enable the FMC/FSMC interface clock */
+ RCC->AHB3ENR |= 0x00000001;
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ /* Configure and enable Bank1_SRAM2 */
+ FMC_Bank1->BTCR[2] = 0x00001011;
+ FMC_Bank1->BTCR[3] = 0x00000201;
+ FMC_Bank1E->BWTR[2] = 0x0fffffff;
+#endif /* STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F40_41xxx)
+ /* Configure and enable Bank1_SRAM2 */
+ FSMC_Bank1->BTCR[2] = 0x00001011;
+ FSMC_Bank1->BTCR[3] = 0x00000201;
+ FSMC_Bank1E->BWTR[2] = 0x0fffffff;
+#endif /* STM32F40_41xxx */
+
+/*
+ Bank1_SRAM2 is configured as follow:
+ In case of FSMC configuration
+ NORSRAMTimingStructure.FSMC_AddressSetupTime = 1;
+ NORSRAMTimingStructure.FSMC_AddressHoldTime = 0;
+ NORSRAMTimingStructure.FSMC_DataSetupTime = 2;
+ NORSRAMTimingStructure.FSMC_BusTurnAroundDuration = 0;
+ NORSRAMTimingStructure.FSMC_CLKDivision = 0;
+ NORSRAMTimingStructure.FSMC_DataLatency = 0;
+ NORSRAMTimingStructure.FSMC_AccessMode = FMC_AccessMode_A;
+
+ FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2;
+ FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_SRAM;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
+ FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+ FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+ FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
+ FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &NORSRAMTimingStructure;
+
+ In case of FMC configuration
+ NORSRAMTimingStructure.FMC_AddressSetupTime = 1;
+ NORSRAMTimingStructure.FMC_AddressHoldTime = 0;
+ NORSRAMTimingStructure.FMC_DataSetupTime = 2;
+ NORSRAMTimingStructure.FMC_BusTurnAroundDuration = 0;
+ NORSRAMTimingStructure.FMC_CLKDivision = 0;
+ NORSRAMTimingStructure.FMC_DataLatency = 0;
+ NORSRAMTimingStructure.FMC_AccessMode = FMC_AccessMode_A;
+
+ FMC_NORSRAMInitStructure.FMC_Bank = FMC_Bank1_NORSRAM2;
+ FMC_NORSRAMInitStructure.FMC_DataAddressMux = FMC_DataAddressMux_Disable;
+ FMC_NORSRAMInitStructure.FMC_MemoryType = FMC_MemoryType_SRAM;
+ FMC_NORSRAMInitStructure.FMC_MemoryDataWidth = FMC_MemoryDataWidth_16b;
+ FMC_NORSRAMInitStructure.FMC_BurstAccessMode = FMC_BurstAccessMode_Disable;
+ FMC_NORSRAMInitStructure.FMC_AsynchronousWait = FMC_AsynchronousWait_Disable;
+ FMC_NORSRAMInitStructure.FMC_WaitSignalPolarity = FMC_WaitSignalPolarity_Low;
+ FMC_NORSRAMInitStructure.FMC_WrapMode = FMC_WrapMode_Disable;
+ FMC_NORSRAMInitStructure.FMC_WaitSignalActive = FMC_WaitSignalActive_BeforeWaitState;
+ FMC_NORSRAMInitStructure.FMC_WriteOperation = FMC_WriteOperation_Enable;
+ FMC_NORSRAMInitStructure.FMC_WaitSignal = FMC_WaitSignal_Disable;
+ FMC_NORSRAMInitStructure.FMC_ExtendedMode = FMC_ExtendedMode_Disable;
+ FMC_NORSRAMInitStructure.FMC_WriteBurst = FMC_WriteBurst_Disable;
+ FMC_NORSRAMInitStructure.FMC_ContinousClock = FMC_CClock_SyncOnly;
+ FMC_NORSRAMInitStructure.FMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
+ FMC_NORSRAMInitStructure.FMC_WriteTimingStruct = &NORSRAMTimingStructure;
+*/
+
+}
+#endif /* DATA_IN_ExtSRAM */
+
+#ifdef DATA_IN_ExtSDRAM
+/**
+ * @brief Setup the external memory controller.
+ * Called in startup_stm32f4xx.s before jump to main.
+ * This function configures the external SDRAM mounted on STM324x9I_EVAL board
+ * This SDRAM will be used as program data memory (including heap and stack).
+ * @param None
+ * @retval None
+ */
+void SystemInit_ExtMemCtl(void)
+{
+ register uint32_t tmpreg = 0, timeout = 0xFFFF;
+ register uint32_t index;
+
+ /* Enable GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface
+ clock */
+ RCC->AHB1ENR |= 0x000001FC;
+
+ /* Connect PCx pins to FMC Alternate function */
+ GPIOC->AFR[0] = 0x0000000c;
+ GPIOC->AFR[1] = 0x00007700;
+ /* Configure PCx pins in Alternate function mode */
+ GPIOC->MODER = 0x00a00002;
+ /* Configure PCx pins speed to 50 MHz */
+ GPIOC->OSPEEDR = 0x00a00002;
+ /* Configure PCx pins Output type to push-pull */
+ GPIOC->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PCx pins */
+ GPIOC->PUPDR = 0x00500000;
+
+ /* Connect PDx pins to FMC Alternate function */
+ GPIOD->AFR[0] = 0x000000CC;
+ GPIOD->AFR[1] = 0xCC000CCC;
+ /* Configure PDx pins in Alternate function mode */
+ GPIOD->MODER = 0xA02A000A;
+ /* Configure PDx pins speed to 50 MHz */
+ GPIOD->OSPEEDR = 0xA02A000A;
+ /* Configure PDx pins Output type to push-pull */
+ GPIOD->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PDx pins */
+ GPIOD->PUPDR = 0x00000000;
+
+ /* Connect PEx pins to FMC Alternate function */
+ GPIOE->AFR[0] = 0xC00000CC;
+ GPIOE->AFR[1] = 0xCCCCCCCC;
+ /* Configure PEx pins in Alternate function mode */
+ GPIOE->MODER = 0xAAAA800A;
+ /* Configure PEx pins speed to 50 MHz */
+ GPIOE->OSPEEDR = 0xAAAA800A;
+ /* Configure PEx pins Output type to push-pull */
+ GPIOE->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PEx pins */
+ GPIOE->PUPDR = 0x00000000;
+
+ /* Connect PFx pins to FMC Alternate function */
+ GPIOF->AFR[0] = 0xcccccccc;
+ GPIOF->AFR[1] = 0xcccccccc;
+ /* Configure PFx pins in Alternate function mode */
+ GPIOF->MODER = 0xAA800AAA;
+ /* Configure PFx pins speed to 50 MHz */
+ GPIOF->OSPEEDR = 0xAA800AAA;
+ /* Configure PFx pins Output type to push-pull */
+ GPIOF->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PFx pins */
+ GPIOF->PUPDR = 0x00000000;
+
+ /* Connect PGx pins to FMC Alternate function */
+ GPIOG->AFR[0] = 0xcccccccc;
+ GPIOG->AFR[1] = 0xcccccccc;
+ /* Configure PGx pins in Alternate function mode */
+ GPIOG->MODER = 0xaaaaaaaa;
+ /* Configure PGx pins speed to 50 MHz */
+ GPIOG->OSPEEDR = 0xaaaaaaaa;
+ /* Configure PGx pins Output type to push-pull */
+ GPIOG->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PGx pins */
+ GPIOG->PUPDR = 0x00000000;
+
+ /* Connect PHx pins to FMC Alternate function */
+ GPIOH->AFR[0] = 0x00C0CC00;
+ GPIOH->AFR[1] = 0xCCCCCCCC;
+ /* Configure PHx pins in Alternate function mode */
+ GPIOH->MODER = 0xAAAA08A0;
+ /* Configure PHx pins speed to 50 MHz */
+ GPIOH->OSPEEDR = 0xAAAA08A0;
+ /* Configure PHx pins Output type to push-pull */
+ GPIOH->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PHx pins */
+ GPIOH->PUPDR = 0x00000000;
+
+ /* Connect PIx pins to FMC Alternate function */
+ GPIOI->AFR[0] = 0xCCCCCCCC;
+ GPIOI->AFR[1] = 0x00000CC0;
+ /* Configure PIx pins in Alternate function mode */
+ GPIOI->MODER = 0x0028AAAA;
+ /* Configure PIx pins speed to 50 MHz */
+ GPIOI->OSPEEDR = 0x0028AAAA;
+ /* Configure PIx pins Output type to push-pull */
+ GPIOI->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PIx pins */
+ GPIOI->PUPDR = 0x00000000;
+
+/*-- FMC Configuration ------------------------------------------------------*/
+ /* Enable the FMC interface clock */
+ RCC->AHB3ENR |= 0x00000001;
+
+ /* Configure and enable SDRAM bank1 */
+ FMC_Bank5_6->SDCR[0] = 0x000039D0;
+ FMC_Bank5_6->SDTR[0] = 0x01115351;
+
+ /* SDRAM initialization sequence */
+ /* Clock enable command */
+ FMC_Bank5_6->SDCMR = 0x00000011;
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Delay */
+ for (index = 0; index<1000; index++);
+
+ /* PALL command */
+ FMC_Bank5_6->SDCMR = 0x00000012;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Auto refresh command */
+ FMC_Bank5_6->SDCMR = 0x00000073;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* MRD register program */
+ FMC_Bank5_6->SDCMR = 0x00046014;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Set refresh count */
+ tmpreg = FMC_Bank5_6->SDRTR;
+ FMC_Bank5_6->SDRTR = (tmpreg | (0x0000027C<<1));
+
+ /* Disable write protection */
+ tmpreg = FMC_Bank5_6->SDCR[0];
+ FMC_Bank5_6->SDCR[0] = (tmpreg & 0xFFFFFDFF);
+
+/*
+ Bank1_SDRAM is configured as follow:
+
+ FMC_SDRAMTimingInitStructure.FMC_LoadToActiveDelay = 2;
+ FMC_SDRAMTimingInitStructure.FMC_ExitSelfRefreshDelay = 6;
+ FMC_SDRAMTimingInitStructure.FMC_SelfRefreshTime = 4;
+ FMC_SDRAMTimingInitStructure.FMC_RowCycleDelay = 6;
+ FMC_SDRAMTimingInitStructure.FMC_WriteRecoveryTime = 2;
+ FMC_SDRAMTimingInitStructure.FMC_RPDelay = 2;
+ FMC_SDRAMTimingInitStructure.FMC_RCDDelay = 2;
+
+ FMC_SDRAMInitStructure.FMC_Bank = SDRAM_BANK;
+ FMC_SDRAMInitStructure.FMC_ColumnBitsNumber = FMC_ColumnBits_Number_8b;
+ FMC_SDRAMInitStructure.FMC_RowBitsNumber = FMC_RowBits_Number_11b;
+ FMC_SDRAMInitStructure.FMC_SDMemoryDataWidth = FMC_SDMemory_Width_16b;
+ FMC_SDRAMInitStructure.FMC_InternalBankNumber = FMC_InternalBank_Number_4;
+ FMC_SDRAMInitStructure.FMC_CASLatency = FMC_CAS_Latency_3;
+ FMC_SDRAMInitStructure.FMC_WriteProtection = FMC_Write_Protection_Disable;
+ FMC_SDRAMInitStructure.FMC_SDClockPeriod = FMC_SDClock_Period_2;
+ FMC_SDRAMInitStructure.FMC_ReadBurst = FMC_Read_Burst_disable;
+ FMC_SDRAMInitStructure.FMC_ReadPipeDelay = FMC_ReadPipe_Delay_1;
+ FMC_SDRAMInitStructure.FMC_SDRAMTimingStruct = &FMC_SDRAMTimingInitStructure;
+*/
+
+}
+#endif /* DATA_IN_ExtSDRAM */
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/src/main/target/BLUEJAYF4/system_stm32f4xx.h b/src/main/target/BLUEJAYF4/system_stm32f4xx.h
new file mode 100644
index 000000000..6d130d851
--- /dev/null
+++ b/src/main/target/BLUEJAYF4/system_stm32f4xx.h
@@ -0,0 +1,45 @@
+/**
+ ******************************************************************************
+ * @file system_stm32f4xx.h
+ * @author MCD Application Team
+ * @version V1.6.1
+ * @date 21-October-2015
+ * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT 2015 STMicroelectronics
+ *
+ * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+ * You may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at:
+ *
+ * http://www.st.com/software_license_agreement_liberty_v2
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ ******************************************************************************
+ */
+
+#ifndef __SYSTEM_STM32F4XX_H
+#define __SYSTEM_STM32F4XX_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
+extern void SystemInit(void);
+extern void SystemCoreClockUpdate(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__SYSTEM_STM32F4XX_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/src/main/target/KKNGF4/system_stm32f4xx.c b/src/main/target/KKNGF4/system_stm32f4xx.c
new file mode 100644
index 000000000..33169994a
--- /dev/null
+++ b/src/main/target/KKNGF4/system_stm32f4xx.c
@@ -0,0 +1,1227 @@
+/**
+ ******************************************************************************
+ * @file system_stm32f4xx.c
+ * @author MCD Application Team
+ * @version V1.6.1
+ * @date 21-October-2015
+ * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
+ * This file contains the system clock configuration for STM32F4xx devices.
+ *
+ * 1. This file provides two functions and one global variable to be called from
+ * user application:
+ * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
+ * and Divider factors, AHB/APBx prescalers and Flash settings),
+ * depending on the configuration made in the clock xls tool.
+ * This function is called at startup just after reset and
+ * before branch to main program. This call is made inside
+ * the "startup_stm32f4xx.s" file.
+ *
+ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+ * by the user application to setup the SysTick
+ * timer or configure other parameters.
+ *
+ * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+ * be called whenever the core clock is changed
+ * during program execution.
+ *
+ * 2. After each device reset the HSI (16 MHz) is used as system clock source.
+ * Then SystemInit() function is called, in "startup_stm32f4xx.s" file, to
+ * configure the system clock before to branch to main program.
+ *
+ * 3. If the system clock source selected by user fails to startup, the SystemInit()
+ * function will do nothing and HSI still used as system clock source. User can
+ * add some code to deal with this issue inside the SetSysClock() function.
+ *
+ * 4. The default value of HSE crystal is set to 25MHz, refer to "HSE_VALUE" define
+ * in "stm32f4xx.h" file. When HSE is used as system clock source, directly or
+ * through PLL, and you are using different crystal you have to adapt the HSE
+ * value to your own configuration.
+ *
+ * 5. This file configures the system clock as follows:
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F40xxx/41xxx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 168000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 168000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 4
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 8000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 10
+ *-----------------------------------------------------------------------------
+ * PLL_N | 420
+ *-----------------------------------------------------------------------------
+ * PLL_P | 2
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 5
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F42xxx/43xxx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 4
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 25000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 25
+ *-----------------------------------------------------------------------------
+ * PLL_N | 360
+ *-----------------------------------------------------------------------------
+ * PLL_P | 2
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 5
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F401xx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 84000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 84000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 25000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 25
+ *-----------------------------------------------------------------------------
+ * PLL_N | 336
+ *-----------------------------------------------------------------------------
+ * PLL_P | 4
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 2
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F411xx/STM32F410xx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSI)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 100000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 100000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * HSI Frequency(Hz) | 16000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 16
+ *-----------------------------------------------------------------------------
+ * PLL_N | 400
+ *-----------------------------------------------------------------------------
+ * PLL_P | 4
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 3
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F446xx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 4
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 8000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 8
+ *-----------------------------------------------------------------------------
+ * PLL_N | 360
+ *-----------------------------------------------------------------------------
+ * PLL_P | 2
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLL_R | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_M | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_P | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_Q | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 5
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT 2015 STMicroelectronics
+ *
+ * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+ * You may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at:
+ *
+ * http://www.st.com/software_license_agreement_liberty_v2
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f4xx_system
+ * @{
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Includes
+ * @{
+ */
+
+#include "stm32f4xx.h"
+
+uint32_t hse_value = HSE_VALUE;
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Defines
+ * @{
+ */
+
+/************************* Miscellaneous Configuration ************************/
+/*!< Uncomment the following line if you need to use external SRAM or SDRAM mounted
+ on STM324xG_EVAL/STM324x7I_EVAL/STM324x9I_EVAL boards as data memory */
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx)
+/* #define DATA_IN_ExtSRAM */
+#endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F469_479xx */
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+/* #define DATA_IN_ExtSDRAM */
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F410xx) || defined(STM32F411xE)
+/*!< Uncomment the following line if you need to clock the STM32F410xx/STM32F411xE by HSE Bypass
+ through STLINK MCO pin of STM32F103 microcontroller. The frequency cannot be changed
+ and is fixed at 8 MHz.
+ Hardware configuration needed for Nucleo Board:
+ – SB54, SB55 OFF
+ – R35 removed
+ – SB16, SB50 ON */
+/* #define USE_HSE_BYPASS */
+
+#if defined(USE_HSE_BYPASS)
+#define HSE_BYPASS_INPUT_FREQUENCY 8000000
+#endif /* USE_HSE_BYPASS */
+#endif /* STM32F410xx || STM32F411xE */
+
+/*!< Uncomment the following line if you need to relocate your vector Table in
+ Internal SRAM. */
+/* #define VECT_TAB_SRAM */
+#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
+ This value must be a multiple of 0x200. */
+/******************************************************************************/
+
+/************************* PLL Parameters *************************************/
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx)
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
+ #define PLL_M 8
+#elif defined (STM32F446xx)
+ #define PLL_M 8
+#elif defined (STM32F410xx) || defined (STM32F411xE)
+ #if defined(USE_HSE_BYPASS)
+ #define PLL_M 8
+ #else /* !USE_HSE_BYPASS */
+ #define PLL_M 8
+ #endif /* USE_HSE_BYPASS */
+#else
+#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F469_479xx */
+
+/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
+#define PLL_Q 8
+
+#if defined(STM32F446xx)
+/* PLL division factor for I2S, SAI, SYSTEM and SPDIF: Clock = PLL_VCO / PLLR */
+#define PLL_R 7
+#endif /* STM32F446xx */
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+#define PLL_N 360
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 2
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined (STM32F40_41xxx)
+#define PLL_N 384
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 2
+#endif /* STM32F40_41xxx */
+
+#if defined(STM32F401xx)
+#define PLL_N 336
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 4
+#endif /* STM32F401xx */
+
+#if defined(STM32F410xx) || defined(STM32F411xE)
+#define PLL_N 400
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 4
+#endif /* STM32F410xx || STM32F411xE */
+
+/******************************************************************************/
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Variables
+ * @{
+ */
+
+#if defined(STM32F40_41xxx)
+ uint32_t SystemCoreClock = 192000000;
+#endif /* STM32F40_41xxx */
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ uint32_t SystemCoreClock = 180000000;
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F401xx)
+ uint32_t SystemCoreClock = 84000000;
+#endif /* STM32F401xx */
+
+#if defined(STM32F410xx) || defined(STM32F411xE)
+ uint32_t SystemCoreClock = 100000000;
+#endif /* STM32F410xx || STM32F401xE */
+
+__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_FunctionPrototypes
+ * @{
+ */
+
+void SetSysClock(void);
+
+#if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
+static void SystemInit_ExtMemCtl(void);
+#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system
+ * Initialize the Embedded Flash Interface, the PLL and update the
+ * SystemFrequency variable.
+ * @param None
+ * @retval None
+ */
+void SystemInit(void)
+{
+ /* FPU settings ------------------------------------------------------------*/
+ #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
+ #endif
+ /* Reset the RCC clock configuration to the default reset state ------------*/
+ /* Set HSION bit */
+ RCC->CR |= (uint32_t)0x00000001;
+
+ /* Reset CFGR register */
+ RCC->CFGR = 0x00000000;
+
+ /* Reset HSEON, CSSON and PLLON bits */
+ RCC->CR &= (uint32_t)0xFEF6FFFF;
+
+ /* Reset PLLCFGR register */
+ RCC->PLLCFGR = 0x24003010;
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= (uint32_t)0xFFFBFFFF;
+
+ /* Disable all interrupts */
+ RCC->CIR = 0x00000000;
+
+#if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
+ SystemInit_ExtMemCtl();
+#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
+
+ /* Configure the System clock source, PLL Multiplier and Divider factors,
+ AHB/APBx prescalers and Flash settings ----------------------------------*/
+ SetSysClock();
+
+ /* Configure the Vector Table location add offset address ------------------*/
+#ifdef VECT_TAB_SRAM
+ SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
+#else
+ SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
+#endif
+}
+
+/**
+ * @brief Update SystemCoreClock variable according to Clock Register Values.
+ * The SystemCoreClock variable contains the core clock (HCLK), it can
+ * be used by the user application to setup the SysTick timer or configure
+ * other parameters.
+ *
+ * @note Each time the core clock (HCLK) changes, this function must be called
+ * to update SystemCoreClock variable value. Otherwise, any configuration
+ * based on this variable will be incorrect.
+ *
+ * @note - The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ *
+ * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
+ *
+ * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
+ *
+ * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
+ * or HSI_VALUE(*) multiplied/divided by the PLL factors.
+ *
+ * (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value
+ * 16 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value
+ * 25 MHz), user has to ensure that HSE_VALUE is same as the real
+ * frequency of the crystal used. Otherwise, this function may
+ * have wrong result.
+ *
+ * - The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ *
+ * @param None
+ * @retval None
+ */
+void SystemCoreClockUpdate(void)
+{
+ uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
+#if defined(STM32F446xx)
+ uint32_t pllr = 2;
+#endif /* STM32F446xx */
+ /* Get SYSCLK source -------------------------------------------------------*/
+ tmp = RCC->CFGR & RCC_CFGR_SWS;
+
+ switch (tmp)
+ {
+ case 0x00: /* HSI used as system clock source */
+ SystemCoreClock = HSI_VALUE;
+ break;
+ case 0x04: /* HSE used as system clock source */
+ SystemCoreClock = HSE_VALUE;
+ break;
+ case 0x08: /* PLL P used as system clock source */
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
+ SYSCLK = PLL_VCO / PLL_P
+ */
+ pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
+ pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
+
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+ else
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+#elif defined(STM32F410xx) || defined(STM32F411xE)
+#if defined(USE_HSE_BYPASS)
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_BYPASS_INPUT_FREQUENCY / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+#else
+ if (pllsource == 0)
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+#endif /* USE_HSE_BYPASS */
+#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F446xx || STM32F469_479xx */
+ pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
+ SystemCoreClock = pllvco/pllp;
+ break;
+#if defined(STM32F446xx)
+ case 0x0C: /* PLL R used as system clock source */
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
+ SYSCLK = PLL_VCO / PLL_R
+ */
+ pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
+ pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+ else
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+
+ pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >>28) + 1 ) *2;
+ SystemCoreClock = pllvco/pllr;
+ break;
+#endif /* STM32F446xx */
+ default:
+ SystemCoreClock = HSI_VALUE;
+ break;
+ }
+ /* Compute HCLK frequency --------------------------------------------------*/
+ /* Get HCLK prescaler */
+ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
+ /* HCLK frequency */
+ SystemCoreClock >>= tmp;
+}
+
+/**
+ * @brief Configures the System clock source, PLL Multiplier and Divider factors,
+ * AHB/APBx prescalers and Flash settings
+ * @Note This function should be called only once the RCC clock configuration
+ * is reset to the default reset state (done in SystemInit() function).
+ * @param None
+ * @retval None
+ */
+void SetSysClock(void)
+{
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F446xx)|| defined(STM32F469_479xx)
+/******************************************************************************/
+/* PLL (clocked by HSE) used as System clock source */
+/******************************************************************************/
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* Enable HSE */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+ /* Select regulator voltage output Scale 1 mode */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+ PWR->CR |= PWR_CR_VOS;
+
+ /* HCLK = SYSCLK / 1*/
+ RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
+#endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F401xx)
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+#endif /* STM32F401xx */
+
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx)
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+ (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
+#endif /* STM32F40_41xxx || STM32F401xx || STM32F427_437x || STM32F429_439xx || STM32F469_479xx */
+
+#if defined(STM32F446xx)
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+ (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24) | (PLL_R << 28);
+#endif /* STM32F446xx */
+
+ /* Enable the main PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till the main PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ /* Enable the Over-drive to extend the clock frequency to 180 Mhz */
+ PWR->CR |= PWR_CR_ODEN;
+ while((PWR->CSR & PWR_CSR_ODRDY) == 0)
+ {
+ }
+ PWR->CR |= PWR_CR_ODSWEN;
+ while((PWR->CSR & PWR_CSR_ODSWRDY) == 0)
+ {
+ }
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F40_41xxx)
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
+#endif /* STM32F40_41xxx */
+
+#if defined(STM32F401xx)
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+#endif /* STM32F401xx */
+
+ /* Select the main PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ /* Wait till the main PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+#elif defined(STM32F410xx) || defined(STM32F411xE)
+#if defined(USE_HSE_BYPASS)
+/******************************************************************************/
+/* PLL (clocked by HSE) used as System clock source */
+/******************************************************************************/
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* Enable HSE and HSE BYPASS */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON | RCC_CR_HSEBYP);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+ /* Select regulator voltage output Scale 1 mode */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+ PWR->CR |= PWR_CR_VOS;
+
+ /* HCLK = SYSCLK / 1*/
+ RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+ (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
+
+ /* Enable the main PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till the main PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+
+ /* Select the main PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ /* Wait till the main PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+#else /* HSI will be used as PLL clock source */
+ /* Select regulator voltage output Scale 1 mode */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+ PWR->CR |= PWR_CR_VOS;
+
+ /* HCLK = SYSCLK / 1*/
+ RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) | (PLL_Q << 24);
+
+ /* Enable the main PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till the main PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+
+ /* Select the main PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ /* Wait till the main PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+ {
+ }
+#endif /* USE_HSE_BYPASS */
+#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F469_479xx */
+}
+
+/**
+ * @brief Setup the external memory controller. Called in startup_stm32f4xx.s
+ * before jump to __main
+ * @param None
+ * @retval None
+ */
+#ifdef DATA_IN_ExtSRAM
+/**
+ * @brief Setup the external memory controller.
+ * Called in startup_stm32f4xx.s before jump to main.
+ * This function configures the external SRAM mounted on STM324xG_EVAL/STM324x7I boards
+ * This SRAM will be used as program data memory (including heap and stack).
+ * @param None
+ * @retval None
+ */
+void SystemInit_ExtMemCtl(void)
+{
+/*-- GPIOs Configuration -----------------------------------------------------*/
+/*
+ +-------------------+--------------------+------------------+--------------+
+ + SRAM pins assignment +
+ +-------------------+--------------------+------------------+--------------+
+ | PD0 <-> FMC_D2 | PE0 <-> FMC_NBL0 | PF0 <-> FMC_A0 | PG0 <-> FMC_A10 |
+ | PD1 <-> FMC_D3 | PE1 <-> FMC_NBL1 | PF1 <-> FMC_A1 | PG1 <-> FMC_A11 |
+ | PD4 <-> FMC_NOE | PE3 <-> FMC_A19 | PF2 <-> FMC_A2 | PG2 <-> FMC_A12 |
+ | PD5 <-> FMC_NWE | PE4 <-> FMC_A20 | PF3 <-> FMC_A3 | PG3 <-> FMC_A13 |
+ | PD8 <-> FMC_D13 | PE7 <-> FMC_D4 | PF4 <-> FMC_A4 | PG4 <-> FMC_A14 |
+ | PD9 <-> FMC_D14 | PE8 <-> FMC_D5 | PF5 <-> FMC_A5 | PG5 <-> FMC_A15 |
+ | PD10 <-> FMC_D15 | PE9 <-> FMC_D6 | PF12 <-> FMC_A6 | PG9 <-> FMC_NE2 |
+ | PD11 <-> FMC_A16 | PE10 <-> FMC_D7 | PF13 <-> FMC_A7 |-----------------+
+ | PD12 <-> FMC_A17 | PE11 <-> FMC_D8 | PF14 <-> FMC_A8 |
+ | PD13 <-> FMC_A18 | PE12 <-> FMC_D9 | PF15 <-> FMC_A9 |
+ | PD14 <-> FMC_D0 | PE13 <-> FMC_D10 |-----------------+
+ | PD15 <-> FMC_D1 | PE14 <-> FMC_D11 |
+ | | PE15 <-> FMC_D12 |
+ +------------------+------------------+
+*/
+ /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
+ RCC->AHB1ENR |= 0x00000078;
+
+ /* Connect PDx pins to FMC Alternate function */
+ GPIOD->AFR[0] = 0x00cc00cc;
+ GPIOD->AFR[1] = 0xcccccccc;
+ /* Configure PDx pins in Alternate function mode */
+ GPIOD->MODER = 0xaaaa0a0a;
+ /* Configure PDx pins speed to 100 MHz */
+ GPIOD->OSPEEDR = 0xffff0f0f;
+ /* Configure PDx pins Output type to push-pull */
+ GPIOD->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PDx pins */
+ GPIOD->PUPDR = 0x00000000;
+
+ /* Connect PEx pins to FMC Alternate function */
+ GPIOE->AFR[0] = 0xcccccccc;
+ GPIOE->AFR[1] = 0xcccccccc;
+ /* Configure PEx pins in Alternate function mode */
+ GPIOE->MODER = 0xaaaaaaaa;
+ /* Configure PEx pins speed to 100 MHz */
+ GPIOE->OSPEEDR = 0xffffffff;
+ /* Configure PEx pins Output type to push-pull */
+ GPIOE->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PEx pins */
+ GPIOE->PUPDR = 0x00000000;
+
+ /* Connect PFx pins to FMC Alternate function */
+ GPIOF->AFR[0] = 0x00cccccc;
+ GPIOF->AFR[1] = 0xcccc0000;
+ /* Configure PFx pins in Alternate function mode */
+ GPIOF->MODER = 0xaa000aaa;
+ /* Configure PFx pins speed to 100 MHz */
+ GPIOF->OSPEEDR = 0xff000fff;
+ /* Configure PFx pins Output type to push-pull */
+ GPIOF->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PFx pins */
+ GPIOF->PUPDR = 0x00000000;
+
+ /* Connect PGx pins to FMC Alternate function */
+ GPIOG->AFR[0] = 0x00cccccc;
+ GPIOG->AFR[1] = 0x000000c0;
+ /* Configure PGx pins in Alternate function mode */
+ GPIOG->MODER = 0x00080aaa;
+ /* Configure PGx pins speed to 100 MHz */
+ GPIOG->OSPEEDR = 0x000c0fff;
+ /* Configure PGx pins Output type to push-pull */
+ GPIOG->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PGx pins */
+ GPIOG->PUPDR = 0x00000000;
+
+/*-- FMC Configuration ------------------------------------------------------*/
+ /* Enable the FMC/FSMC interface clock */
+ RCC->AHB3ENR |= 0x00000001;
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ /* Configure and enable Bank1_SRAM2 */
+ FMC_Bank1->BTCR[2] = 0x00001011;
+ FMC_Bank1->BTCR[3] = 0x00000201;
+ FMC_Bank1E->BWTR[2] = 0x0fffffff;
+#endif /* STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F40_41xxx)
+ /* Configure and enable Bank1_SRAM2 */
+ FSMC_Bank1->BTCR[2] = 0x00001011;
+ FSMC_Bank1->BTCR[3] = 0x00000201;
+ FSMC_Bank1E->BWTR[2] = 0x0fffffff;
+#endif /* STM32F40_41xxx */
+
+/*
+ Bank1_SRAM2 is configured as follow:
+ In case of FSMC configuration
+ NORSRAMTimingStructure.FSMC_AddressSetupTime = 1;
+ NORSRAMTimingStructure.FSMC_AddressHoldTime = 0;
+ NORSRAMTimingStructure.FSMC_DataSetupTime = 2;
+ NORSRAMTimingStructure.FSMC_BusTurnAroundDuration = 0;
+ NORSRAMTimingStructure.FSMC_CLKDivision = 0;
+ NORSRAMTimingStructure.FSMC_DataLatency = 0;
+ NORSRAMTimingStructure.FSMC_AccessMode = FMC_AccessMode_A;
+
+ FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2;
+ FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_SRAM;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
+ FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+ FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+ FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
+ FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &NORSRAMTimingStructure;
+
+ In case of FMC configuration
+ NORSRAMTimingStructure.FMC_AddressSetupTime = 1;
+ NORSRAMTimingStructure.FMC_AddressHoldTime = 0;
+ NORSRAMTimingStructure.FMC_DataSetupTime = 2;
+ NORSRAMTimingStructure.FMC_BusTurnAroundDuration = 0;
+ NORSRAMTimingStructure.FMC_CLKDivision = 0;
+ NORSRAMTimingStructure.FMC_DataLatency = 0;
+ NORSRAMTimingStructure.FMC_AccessMode = FMC_AccessMode_A;
+
+ FMC_NORSRAMInitStructure.FMC_Bank = FMC_Bank1_NORSRAM2;
+ FMC_NORSRAMInitStructure.FMC_DataAddressMux = FMC_DataAddressMux_Disable;
+ FMC_NORSRAMInitStructure.FMC_MemoryType = FMC_MemoryType_SRAM;
+ FMC_NORSRAMInitStructure.FMC_MemoryDataWidth = FMC_MemoryDataWidth_16b;
+ FMC_NORSRAMInitStructure.FMC_BurstAccessMode = FMC_BurstAccessMode_Disable;
+ FMC_NORSRAMInitStructure.FMC_AsynchronousWait = FMC_AsynchronousWait_Disable;
+ FMC_NORSRAMInitStructure.FMC_WaitSignalPolarity = FMC_WaitSignalPolarity_Low;
+ FMC_NORSRAMInitStructure.FMC_WrapMode = FMC_WrapMode_Disable;
+ FMC_NORSRAMInitStructure.FMC_WaitSignalActive = FMC_WaitSignalActive_BeforeWaitState;
+ FMC_NORSRAMInitStructure.FMC_WriteOperation = FMC_WriteOperation_Enable;
+ FMC_NORSRAMInitStructure.FMC_WaitSignal = FMC_WaitSignal_Disable;
+ FMC_NORSRAMInitStructure.FMC_ExtendedMode = FMC_ExtendedMode_Disable;
+ FMC_NORSRAMInitStructure.FMC_WriteBurst = FMC_WriteBurst_Disable;
+ FMC_NORSRAMInitStructure.FMC_ContinousClock = FMC_CClock_SyncOnly;
+ FMC_NORSRAMInitStructure.FMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
+ FMC_NORSRAMInitStructure.FMC_WriteTimingStruct = &NORSRAMTimingStructure;
+*/
+
+}
+#endif /* DATA_IN_ExtSRAM */
+
+#ifdef DATA_IN_ExtSDRAM
+/**
+ * @brief Setup the external memory controller.
+ * Called in startup_stm32f4xx.s before jump to main.
+ * This function configures the external SDRAM mounted on STM324x9I_EVAL board
+ * This SDRAM will be used as program data memory (including heap and stack).
+ * @param None
+ * @retval None
+ */
+void SystemInit_ExtMemCtl(void)
+{
+ register uint32_t tmpreg = 0, timeout = 0xFFFF;
+ register uint32_t index;
+
+ /* Enable GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface
+ clock */
+ RCC->AHB1ENR |= 0x000001FC;
+
+ /* Connect PCx pins to FMC Alternate function */
+ GPIOC->AFR[0] = 0x0000000c;
+ GPIOC->AFR[1] = 0x00007700;
+ /* Configure PCx pins in Alternate function mode */
+ GPIOC->MODER = 0x00a00002;
+ /* Configure PCx pins speed to 50 MHz */
+ GPIOC->OSPEEDR = 0x00a00002;
+ /* Configure PCx pins Output type to push-pull */
+ GPIOC->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PCx pins */
+ GPIOC->PUPDR = 0x00500000;
+
+ /* Connect PDx pins to FMC Alternate function */
+ GPIOD->AFR[0] = 0x000000CC;
+ GPIOD->AFR[1] = 0xCC000CCC;
+ /* Configure PDx pins in Alternate function mode */
+ GPIOD->MODER = 0xA02A000A;
+ /* Configure PDx pins speed to 50 MHz */
+ GPIOD->OSPEEDR = 0xA02A000A;
+ /* Configure PDx pins Output type to push-pull */
+ GPIOD->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PDx pins */
+ GPIOD->PUPDR = 0x00000000;
+
+ /* Connect PEx pins to FMC Alternate function */
+ GPIOE->AFR[0] = 0xC00000CC;
+ GPIOE->AFR[1] = 0xCCCCCCCC;
+ /* Configure PEx pins in Alternate function mode */
+ GPIOE->MODER = 0xAAAA800A;
+ /* Configure PEx pins speed to 50 MHz */
+ GPIOE->OSPEEDR = 0xAAAA800A;
+ /* Configure PEx pins Output type to push-pull */
+ GPIOE->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PEx pins */
+ GPIOE->PUPDR = 0x00000000;
+
+ /* Connect PFx pins to FMC Alternate function */
+ GPIOF->AFR[0] = 0xcccccccc;
+ GPIOF->AFR[1] = 0xcccccccc;
+ /* Configure PFx pins in Alternate function mode */
+ GPIOF->MODER = 0xAA800AAA;
+ /* Configure PFx pins speed to 50 MHz */
+ GPIOF->OSPEEDR = 0xAA800AAA;
+ /* Configure PFx pins Output type to push-pull */
+ GPIOF->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PFx pins */
+ GPIOF->PUPDR = 0x00000000;
+
+ /* Connect PGx pins to FMC Alternate function */
+ GPIOG->AFR[0] = 0xcccccccc;
+ GPIOG->AFR[1] = 0xcccccccc;
+ /* Configure PGx pins in Alternate function mode */
+ GPIOG->MODER = 0xaaaaaaaa;
+ /* Configure PGx pins speed to 50 MHz */
+ GPIOG->OSPEEDR = 0xaaaaaaaa;
+ /* Configure PGx pins Output type to push-pull */
+ GPIOG->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PGx pins */
+ GPIOG->PUPDR = 0x00000000;
+
+ /* Connect PHx pins to FMC Alternate function */
+ GPIOH->AFR[0] = 0x00C0CC00;
+ GPIOH->AFR[1] = 0xCCCCCCCC;
+ /* Configure PHx pins in Alternate function mode */
+ GPIOH->MODER = 0xAAAA08A0;
+ /* Configure PHx pins speed to 50 MHz */
+ GPIOH->OSPEEDR = 0xAAAA08A0;
+ /* Configure PHx pins Output type to push-pull */
+ GPIOH->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PHx pins */
+ GPIOH->PUPDR = 0x00000000;
+
+ /* Connect PIx pins to FMC Alternate function */
+ GPIOI->AFR[0] = 0xCCCCCCCC;
+ GPIOI->AFR[1] = 0x00000CC0;
+ /* Configure PIx pins in Alternate function mode */
+ GPIOI->MODER = 0x0028AAAA;
+ /* Configure PIx pins speed to 50 MHz */
+ GPIOI->OSPEEDR = 0x0028AAAA;
+ /* Configure PIx pins Output type to push-pull */
+ GPIOI->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PIx pins */
+ GPIOI->PUPDR = 0x00000000;
+
+/*-- FMC Configuration ------------------------------------------------------*/
+ /* Enable the FMC interface clock */
+ RCC->AHB3ENR |= 0x00000001;
+
+ /* Configure and enable SDRAM bank1 */
+ FMC_Bank5_6->SDCR[0] = 0x000039D0;
+ FMC_Bank5_6->SDTR[0] = 0x01115351;
+
+ /* SDRAM initialization sequence */
+ /* Clock enable command */
+ FMC_Bank5_6->SDCMR = 0x00000011;
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Delay */
+ for (index = 0; index<1000; index++);
+
+ /* PALL command */
+ FMC_Bank5_6->SDCMR = 0x00000012;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Auto refresh command */
+ FMC_Bank5_6->SDCMR = 0x00000073;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* MRD register program */
+ FMC_Bank5_6->SDCMR = 0x00046014;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Set refresh count */
+ tmpreg = FMC_Bank5_6->SDRTR;
+ FMC_Bank5_6->SDRTR = (tmpreg | (0x0000027C<<1));
+
+ /* Disable write protection */
+ tmpreg = FMC_Bank5_6->SDCR[0];
+ FMC_Bank5_6->SDCR[0] = (tmpreg & 0xFFFFFDFF);
+
+/*
+ Bank1_SDRAM is configured as follow:
+
+ FMC_SDRAMTimingInitStructure.FMC_LoadToActiveDelay = 2;
+ FMC_SDRAMTimingInitStructure.FMC_ExitSelfRefreshDelay = 6;
+ FMC_SDRAMTimingInitStructure.FMC_SelfRefreshTime = 4;
+ FMC_SDRAMTimingInitStructure.FMC_RowCycleDelay = 6;
+ FMC_SDRAMTimingInitStructure.FMC_WriteRecoveryTime = 2;
+ FMC_SDRAMTimingInitStructure.FMC_RPDelay = 2;
+ FMC_SDRAMTimingInitStructure.FMC_RCDDelay = 2;
+
+ FMC_SDRAMInitStructure.FMC_Bank = SDRAM_BANK;
+ FMC_SDRAMInitStructure.FMC_ColumnBitsNumber = FMC_ColumnBits_Number_8b;
+ FMC_SDRAMInitStructure.FMC_RowBitsNumber = FMC_RowBits_Number_11b;
+ FMC_SDRAMInitStructure.FMC_SDMemoryDataWidth = FMC_SDMemory_Width_16b;
+ FMC_SDRAMInitStructure.FMC_InternalBankNumber = FMC_InternalBank_Number_4;
+ FMC_SDRAMInitStructure.FMC_CASLatency = FMC_CAS_Latency_3;
+ FMC_SDRAMInitStructure.FMC_WriteProtection = FMC_Write_Protection_Disable;
+ FMC_SDRAMInitStructure.FMC_SDClockPeriod = FMC_SDClock_Period_2;
+ FMC_SDRAMInitStructure.FMC_ReadBurst = FMC_Read_Burst_disable;
+ FMC_SDRAMInitStructure.FMC_ReadPipeDelay = FMC_ReadPipe_Delay_1;
+ FMC_SDRAMInitStructure.FMC_SDRAMTimingStruct = &FMC_SDRAMTimingInitStructure;
+*/
+
+}
+#endif /* DATA_IN_ExtSDRAM */
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/src/main/target/KKNGF4/system_stm32f4xx.h b/src/main/target/KKNGF4/system_stm32f4xx.h
new file mode 100644
index 000000000..5e30ef818
--- /dev/null
+++ b/src/main/target/KKNGF4/system_stm32f4xx.h
@@ -0,0 +1,105 @@
+/**
+ ******************************************************************************
+ * @file system_stm32f4xx.h
+ * @author MCD Application Team
+ * @version V1.6.1
+ * @date 21-October-2015
+ * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT 2015 STMicroelectronics
+ *
+ * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+ * You may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at:
+ *
+ * http://www.st.com/software_license_agreement_liberty_v2
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f4xx_system
+ * @{
+ */
+
+/**
+ * @brief Define to prevent recursive inclusion
+ */
+#ifndef __SYSTEM_STM32F4XX_H
+#define __SYSTEM_STM32F4XX_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/** @addtogroup STM32F4xx_System_Includes
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @addtogroup STM32F4xx_System_Exported_types
+ * @{
+ */
+
+extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
+
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Exported_Constants
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Exported_Functions
+ * @{
+ */
+
+extern void SystemInit(void);
+extern void SystemCoreClockUpdate(void);
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__SYSTEM_STM32F4XX_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h
index acd00b7c8..eab30f68d 100644
--- a/src/main/target/NAZE/target.h
+++ b/src/main/target/NAZE/target.h
@@ -181,6 +181,8 @@
#undef TARGET_BOARD_IDENTIFIER
#define TARGET_BOARD_IDENTIFIER "AWF1" // AlienFlight F1.
#undef BOARD_HAS_VOLTAGE_DIVIDER
+#define ALIENFLIGHT
+
#define HARDWARE_BIND_PLUG
// Hardware bind plug at PB5 (Pin 41)
diff --git a/src/main/target/REVO/system_stm32f4xx.c b/src/main/target/REVO/system_stm32f4xx.c
new file mode 100644
index 000000000..33169994a
--- /dev/null
+++ b/src/main/target/REVO/system_stm32f4xx.c
@@ -0,0 +1,1227 @@
+/**
+ ******************************************************************************
+ * @file system_stm32f4xx.c
+ * @author MCD Application Team
+ * @version V1.6.1
+ * @date 21-October-2015
+ * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
+ * This file contains the system clock configuration for STM32F4xx devices.
+ *
+ * 1. This file provides two functions and one global variable to be called from
+ * user application:
+ * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
+ * and Divider factors, AHB/APBx prescalers and Flash settings),
+ * depending on the configuration made in the clock xls tool.
+ * This function is called at startup just after reset and
+ * before branch to main program. This call is made inside
+ * the "startup_stm32f4xx.s" file.
+ *
+ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+ * by the user application to setup the SysTick
+ * timer or configure other parameters.
+ *
+ * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+ * be called whenever the core clock is changed
+ * during program execution.
+ *
+ * 2. After each device reset the HSI (16 MHz) is used as system clock source.
+ * Then SystemInit() function is called, in "startup_stm32f4xx.s" file, to
+ * configure the system clock before to branch to main program.
+ *
+ * 3. If the system clock source selected by user fails to startup, the SystemInit()
+ * function will do nothing and HSI still used as system clock source. User can
+ * add some code to deal with this issue inside the SetSysClock() function.
+ *
+ * 4. The default value of HSE crystal is set to 25MHz, refer to "HSE_VALUE" define
+ * in "stm32f4xx.h" file. When HSE is used as system clock source, directly or
+ * through PLL, and you are using different crystal you have to adapt the HSE
+ * value to your own configuration.
+ *
+ * 5. This file configures the system clock as follows:
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F40xxx/41xxx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 168000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 168000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 4
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 8000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 10
+ *-----------------------------------------------------------------------------
+ * PLL_N | 420
+ *-----------------------------------------------------------------------------
+ * PLL_P | 2
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 5
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F42xxx/43xxx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 4
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 25000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 25
+ *-----------------------------------------------------------------------------
+ * PLL_N | 360
+ *-----------------------------------------------------------------------------
+ * PLL_P | 2
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 5
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F401xx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 84000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 84000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 25000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 25
+ *-----------------------------------------------------------------------------
+ * PLL_N | 336
+ *-----------------------------------------------------------------------------
+ * PLL_P | 4
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 2
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F411xx/STM32F410xx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSI)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 100000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 100000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * HSI Frequency(Hz) | 16000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 16
+ *-----------------------------------------------------------------------------
+ * PLL_N | 400
+ *-----------------------------------------------------------------------------
+ * PLL_P | 4
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 3
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F446xx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 4
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 8000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 8
+ *-----------------------------------------------------------------------------
+ * PLL_N | 360
+ *-----------------------------------------------------------------------------
+ * PLL_P | 2
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLL_R | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_M | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_P | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_Q | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 5
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT 2015 STMicroelectronics
+ *
+ * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+ * You may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at:
+ *
+ * http://www.st.com/software_license_agreement_liberty_v2
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f4xx_system
+ * @{
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Includes
+ * @{
+ */
+
+#include "stm32f4xx.h"
+
+uint32_t hse_value = HSE_VALUE;
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Defines
+ * @{
+ */
+
+/************************* Miscellaneous Configuration ************************/
+/*!< Uncomment the following line if you need to use external SRAM or SDRAM mounted
+ on STM324xG_EVAL/STM324x7I_EVAL/STM324x9I_EVAL boards as data memory */
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx)
+/* #define DATA_IN_ExtSRAM */
+#endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F469_479xx */
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+/* #define DATA_IN_ExtSDRAM */
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F410xx) || defined(STM32F411xE)
+/*!< Uncomment the following line if you need to clock the STM32F410xx/STM32F411xE by HSE Bypass
+ through STLINK MCO pin of STM32F103 microcontroller. The frequency cannot be changed
+ and is fixed at 8 MHz.
+ Hardware configuration needed for Nucleo Board:
+ – SB54, SB55 OFF
+ – R35 removed
+ – SB16, SB50 ON */
+/* #define USE_HSE_BYPASS */
+
+#if defined(USE_HSE_BYPASS)
+#define HSE_BYPASS_INPUT_FREQUENCY 8000000
+#endif /* USE_HSE_BYPASS */
+#endif /* STM32F410xx || STM32F411xE */
+
+/*!< Uncomment the following line if you need to relocate your vector Table in
+ Internal SRAM. */
+/* #define VECT_TAB_SRAM */
+#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
+ This value must be a multiple of 0x200. */
+/******************************************************************************/
+
+/************************* PLL Parameters *************************************/
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx)
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
+ #define PLL_M 8
+#elif defined (STM32F446xx)
+ #define PLL_M 8
+#elif defined (STM32F410xx) || defined (STM32F411xE)
+ #if defined(USE_HSE_BYPASS)
+ #define PLL_M 8
+ #else /* !USE_HSE_BYPASS */
+ #define PLL_M 8
+ #endif /* USE_HSE_BYPASS */
+#else
+#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F469_479xx */
+
+/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
+#define PLL_Q 8
+
+#if defined(STM32F446xx)
+/* PLL division factor for I2S, SAI, SYSTEM and SPDIF: Clock = PLL_VCO / PLLR */
+#define PLL_R 7
+#endif /* STM32F446xx */
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+#define PLL_N 360
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 2
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined (STM32F40_41xxx)
+#define PLL_N 384
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 2
+#endif /* STM32F40_41xxx */
+
+#if defined(STM32F401xx)
+#define PLL_N 336
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 4
+#endif /* STM32F401xx */
+
+#if defined(STM32F410xx) || defined(STM32F411xE)
+#define PLL_N 400
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 4
+#endif /* STM32F410xx || STM32F411xE */
+
+/******************************************************************************/
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Variables
+ * @{
+ */
+
+#if defined(STM32F40_41xxx)
+ uint32_t SystemCoreClock = 192000000;
+#endif /* STM32F40_41xxx */
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ uint32_t SystemCoreClock = 180000000;
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F401xx)
+ uint32_t SystemCoreClock = 84000000;
+#endif /* STM32F401xx */
+
+#if defined(STM32F410xx) || defined(STM32F411xE)
+ uint32_t SystemCoreClock = 100000000;
+#endif /* STM32F410xx || STM32F401xE */
+
+__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_FunctionPrototypes
+ * @{
+ */
+
+void SetSysClock(void);
+
+#if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
+static void SystemInit_ExtMemCtl(void);
+#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system
+ * Initialize the Embedded Flash Interface, the PLL and update the
+ * SystemFrequency variable.
+ * @param None
+ * @retval None
+ */
+void SystemInit(void)
+{
+ /* FPU settings ------------------------------------------------------------*/
+ #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
+ #endif
+ /* Reset the RCC clock configuration to the default reset state ------------*/
+ /* Set HSION bit */
+ RCC->CR |= (uint32_t)0x00000001;
+
+ /* Reset CFGR register */
+ RCC->CFGR = 0x00000000;
+
+ /* Reset HSEON, CSSON and PLLON bits */
+ RCC->CR &= (uint32_t)0xFEF6FFFF;
+
+ /* Reset PLLCFGR register */
+ RCC->PLLCFGR = 0x24003010;
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= (uint32_t)0xFFFBFFFF;
+
+ /* Disable all interrupts */
+ RCC->CIR = 0x00000000;
+
+#if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
+ SystemInit_ExtMemCtl();
+#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
+
+ /* Configure the System clock source, PLL Multiplier and Divider factors,
+ AHB/APBx prescalers and Flash settings ----------------------------------*/
+ SetSysClock();
+
+ /* Configure the Vector Table location add offset address ------------------*/
+#ifdef VECT_TAB_SRAM
+ SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
+#else
+ SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
+#endif
+}
+
+/**
+ * @brief Update SystemCoreClock variable according to Clock Register Values.
+ * The SystemCoreClock variable contains the core clock (HCLK), it can
+ * be used by the user application to setup the SysTick timer or configure
+ * other parameters.
+ *
+ * @note Each time the core clock (HCLK) changes, this function must be called
+ * to update SystemCoreClock variable value. Otherwise, any configuration
+ * based on this variable will be incorrect.
+ *
+ * @note - The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ *
+ * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
+ *
+ * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
+ *
+ * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
+ * or HSI_VALUE(*) multiplied/divided by the PLL factors.
+ *
+ * (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value
+ * 16 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value
+ * 25 MHz), user has to ensure that HSE_VALUE is same as the real
+ * frequency of the crystal used. Otherwise, this function may
+ * have wrong result.
+ *
+ * - The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ *
+ * @param None
+ * @retval None
+ */
+void SystemCoreClockUpdate(void)
+{
+ uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
+#if defined(STM32F446xx)
+ uint32_t pllr = 2;
+#endif /* STM32F446xx */
+ /* Get SYSCLK source -------------------------------------------------------*/
+ tmp = RCC->CFGR & RCC_CFGR_SWS;
+
+ switch (tmp)
+ {
+ case 0x00: /* HSI used as system clock source */
+ SystemCoreClock = HSI_VALUE;
+ break;
+ case 0x04: /* HSE used as system clock source */
+ SystemCoreClock = HSE_VALUE;
+ break;
+ case 0x08: /* PLL P used as system clock source */
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
+ SYSCLK = PLL_VCO / PLL_P
+ */
+ pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
+ pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
+
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+ else
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+#elif defined(STM32F410xx) || defined(STM32F411xE)
+#if defined(USE_HSE_BYPASS)
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_BYPASS_INPUT_FREQUENCY / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+#else
+ if (pllsource == 0)
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+#endif /* USE_HSE_BYPASS */
+#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F446xx || STM32F469_479xx */
+ pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
+ SystemCoreClock = pllvco/pllp;
+ break;
+#if defined(STM32F446xx)
+ case 0x0C: /* PLL R used as system clock source */
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
+ SYSCLK = PLL_VCO / PLL_R
+ */
+ pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
+ pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+ else
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+
+ pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >>28) + 1 ) *2;
+ SystemCoreClock = pllvco/pllr;
+ break;
+#endif /* STM32F446xx */
+ default:
+ SystemCoreClock = HSI_VALUE;
+ break;
+ }
+ /* Compute HCLK frequency --------------------------------------------------*/
+ /* Get HCLK prescaler */
+ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
+ /* HCLK frequency */
+ SystemCoreClock >>= tmp;
+}
+
+/**
+ * @brief Configures the System clock source, PLL Multiplier and Divider factors,
+ * AHB/APBx prescalers and Flash settings
+ * @Note This function should be called only once the RCC clock configuration
+ * is reset to the default reset state (done in SystemInit() function).
+ * @param None
+ * @retval None
+ */
+void SetSysClock(void)
+{
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F446xx)|| defined(STM32F469_479xx)
+/******************************************************************************/
+/* PLL (clocked by HSE) used as System clock source */
+/******************************************************************************/
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* Enable HSE */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+ /* Select regulator voltage output Scale 1 mode */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+ PWR->CR |= PWR_CR_VOS;
+
+ /* HCLK = SYSCLK / 1*/
+ RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
+#endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F401xx)
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+#endif /* STM32F401xx */
+
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx)
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+ (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
+#endif /* STM32F40_41xxx || STM32F401xx || STM32F427_437x || STM32F429_439xx || STM32F469_479xx */
+
+#if defined(STM32F446xx)
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+ (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24) | (PLL_R << 28);
+#endif /* STM32F446xx */
+
+ /* Enable the main PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till the main PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ /* Enable the Over-drive to extend the clock frequency to 180 Mhz */
+ PWR->CR |= PWR_CR_ODEN;
+ while((PWR->CSR & PWR_CSR_ODRDY) == 0)
+ {
+ }
+ PWR->CR |= PWR_CR_ODSWEN;
+ while((PWR->CSR & PWR_CSR_ODSWRDY) == 0)
+ {
+ }
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F40_41xxx)
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
+#endif /* STM32F40_41xxx */
+
+#if defined(STM32F401xx)
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+#endif /* STM32F401xx */
+
+ /* Select the main PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ /* Wait till the main PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+#elif defined(STM32F410xx) || defined(STM32F411xE)
+#if defined(USE_HSE_BYPASS)
+/******************************************************************************/
+/* PLL (clocked by HSE) used as System clock source */
+/******************************************************************************/
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* Enable HSE and HSE BYPASS */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON | RCC_CR_HSEBYP);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+ /* Select regulator voltage output Scale 1 mode */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+ PWR->CR |= PWR_CR_VOS;
+
+ /* HCLK = SYSCLK / 1*/
+ RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+ (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
+
+ /* Enable the main PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till the main PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+
+ /* Select the main PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ /* Wait till the main PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+#else /* HSI will be used as PLL clock source */
+ /* Select regulator voltage output Scale 1 mode */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+ PWR->CR |= PWR_CR_VOS;
+
+ /* HCLK = SYSCLK / 1*/
+ RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) | (PLL_Q << 24);
+
+ /* Enable the main PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till the main PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+
+ /* Select the main PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ /* Wait till the main PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+ {
+ }
+#endif /* USE_HSE_BYPASS */
+#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F469_479xx */
+}
+
+/**
+ * @brief Setup the external memory controller. Called in startup_stm32f4xx.s
+ * before jump to __main
+ * @param None
+ * @retval None
+ */
+#ifdef DATA_IN_ExtSRAM
+/**
+ * @brief Setup the external memory controller.
+ * Called in startup_stm32f4xx.s before jump to main.
+ * This function configures the external SRAM mounted on STM324xG_EVAL/STM324x7I boards
+ * This SRAM will be used as program data memory (including heap and stack).
+ * @param None
+ * @retval None
+ */
+void SystemInit_ExtMemCtl(void)
+{
+/*-- GPIOs Configuration -----------------------------------------------------*/
+/*
+ +-------------------+--------------------+------------------+--------------+
+ + SRAM pins assignment +
+ +-------------------+--------------------+------------------+--------------+
+ | PD0 <-> FMC_D2 | PE0 <-> FMC_NBL0 | PF0 <-> FMC_A0 | PG0 <-> FMC_A10 |
+ | PD1 <-> FMC_D3 | PE1 <-> FMC_NBL1 | PF1 <-> FMC_A1 | PG1 <-> FMC_A11 |
+ | PD4 <-> FMC_NOE | PE3 <-> FMC_A19 | PF2 <-> FMC_A2 | PG2 <-> FMC_A12 |
+ | PD5 <-> FMC_NWE | PE4 <-> FMC_A20 | PF3 <-> FMC_A3 | PG3 <-> FMC_A13 |
+ | PD8 <-> FMC_D13 | PE7 <-> FMC_D4 | PF4 <-> FMC_A4 | PG4 <-> FMC_A14 |
+ | PD9 <-> FMC_D14 | PE8 <-> FMC_D5 | PF5 <-> FMC_A5 | PG5 <-> FMC_A15 |
+ | PD10 <-> FMC_D15 | PE9 <-> FMC_D6 | PF12 <-> FMC_A6 | PG9 <-> FMC_NE2 |
+ | PD11 <-> FMC_A16 | PE10 <-> FMC_D7 | PF13 <-> FMC_A7 |-----------------+
+ | PD12 <-> FMC_A17 | PE11 <-> FMC_D8 | PF14 <-> FMC_A8 |
+ | PD13 <-> FMC_A18 | PE12 <-> FMC_D9 | PF15 <-> FMC_A9 |
+ | PD14 <-> FMC_D0 | PE13 <-> FMC_D10 |-----------------+
+ | PD15 <-> FMC_D1 | PE14 <-> FMC_D11 |
+ | | PE15 <-> FMC_D12 |
+ +------------------+------------------+
+*/
+ /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
+ RCC->AHB1ENR |= 0x00000078;
+
+ /* Connect PDx pins to FMC Alternate function */
+ GPIOD->AFR[0] = 0x00cc00cc;
+ GPIOD->AFR[1] = 0xcccccccc;
+ /* Configure PDx pins in Alternate function mode */
+ GPIOD->MODER = 0xaaaa0a0a;
+ /* Configure PDx pins speed to 100 MHz */
+ GPIOD->OSPEEDR = 0xffff0f0f;
+ /* Configure PDx pins Output type to push-pull */
+ GPIOD->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PDx pins */
+ GPIOD->PUPDR = 0x00000000;
+
+ /* Connect PEx pins to FMC Alternate function */
+ GPIOE->AFR[0] = 0xcccccccc;
+ GPIOE->AFR[1] = 0xcccccccc;
+ /* Configure PEx pins in Alternate function mode */
+ GPIOE->MODER = 0xaaaaaaaa;
+ /* Configure PEx pins speed to 100 MHz */
+ GPIOE->OSPEEDR = 0xffffffff;
+ /* Configure PEx pins Output type to push-pull */
+ GPIOE->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PEx pins */
+ GPIOE->PUPDR = 0x00000000;
+
+ /* Connect PFx pins to FMC Alternate function */
+ GPIOF->AFR[0] = 0x00cccccc;
+ GPIOF->AFR[1] = 0xcccc0000;
+ /* Configure PFx pins in Alternate function mode */
+ GPIOF->MODER = 0xaa000aaa;
+ /* Configure PFx pins speed to 100 MHz */
+ GPIOF->OSPEEDR = 0xff000fff;
+ /* Configure PFx pins Output type to push-pull */
+ GPIOF->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PFx pins */
+ GPIOF->PUPDR = 0x00000000;
+
+ /* Connect PGx pins to FMC Alternate function */
+ GPIOG->AFR[0] = 0x00cccccc;
+ GPIOG->AFR[1] = 0x000000c0;
+ /* Configure PGx pins in Alternate function mode */
+ GPIOG->MODER = 0x00080aaa;
+ /* Configure PGx pins speed to 100 MHz */
+ GPIOG->OSPEEDR = 0x000c0fff;
+ /* Configure PGx pins Output type to push-pull */
+ GPIOG->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PGx pins */
+ GPIOG->PUPDR = 0x00000000;
+
+/*-- FMC Configuration ------------------------------------------------------*/
+ /* Enable the FMC/FSMC interface clock */
+ RCC->AHB3ENR |= 0x00000001;
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ /* Configure and enable Bank1_SRAM2 */
+ FMC_Bank1->BTCR[2] = 0x00001011;
+ FMC_Bank1->BTCR[3] = 0x00000201;
+ FMC_Bank1E->BWTR[2] = 0x0fffffff;
+#endif /* STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F40_41xxx)
+ /* Configure and enable Bank1_SRAM2 */
+ FSMC_Bank1->BTCR[2] = 0x00001011;
+ FSMC_Bank1->BTCR[3] = 0x00000201;
+ FSMC_Bank1E->BWTR[2] = 0x0fffffff;
+#endif /* STM32F40_41xxx */
+
+/*
+ Bank1_SRAM2 is configured as follow:
+ In case of FSMC configuration
+ NORSRAMTimingStructure.FSMC_AddressSetupTime = 1;
+ NORSRAMTimingStructure.FSMC_AddressHoldTime = 0;
+ NORSRAMTimingStructure.FSMC_DataSetupTime = 2;
+ NORSRAMTimingStructure.FSMC_BusTurnAroundDuration = 0;
+ NORSRAMTimingStructure.FSMC_CLKDivision = 0;
+ NORSRAMTimingStructure.FSMC_DataLatency = 0;
+ NORSRAMTimingStructure.FSMC_AccessMode = FMC_AccessMode_A;
+
+ FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2;
+ FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_SRAM;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
+ FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+ FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+ FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
+ FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &NORSRAMTimingStructure;
+
+ In case of FMC configuration
+ NORSRAMTimingStructure.FMC_AddressSetupTime = 1;
+ NORSRAMTimingStructure.FMC_AddressHoldTime = 0;
+ NORSRAMTimingStructure.FMC_DataSetupTime = 2;
+ NORSRAMTimingStructure.FMC_BusTurnAroundDuration = 0;
+ NORSRAMTimingStructure.FMC_CLKDivision = 0;
+ NORSRAMTimingStructure.FMC_DataLatency = 0;
+ NORSRAMTimingStructure.FMC_AccessMode = FMC_AccessMode_A;
+
+ FMC_NORSRAMInitStructure.FMC_Bank = FMC_Bank1_NORSRAM2;
+ FMC_NORSRAMInitStructure.FMC_DataAddressMux = FMC_DataAddressMux_Disable;
+ FMC_NORSRAMInitStructure.FMC_MemoryType = FMC_MemoryType_SRAM;
+ FMC_NORSRAMInitStructure.FMC_MemoryDataWidth = FMC_MemoryDataWidth_16b;
+ FMC_NORSRAMInitStructure.FMC_BurstAccessMode = FMC_BurstAccessMode_Disable;
+ FMC_NORSRAMInitStructure.FMC_AsynchronousWait = FMC_AsynchronousWait_Disable;
+ FMC_NORSRAMInitStructure.FMC_WaitSignalPolarity = FMC_WaitSignalPolarity_Low;
+ FMC_NORSRAMInitStructure.FMC_WrapMode = FMC_WrapMode_Disable;
+ FMC_NORSRAMInitStructure.FMC_WaitSignalActive = FMC_WaitSignalActive_BeforeWaitState;
+ FMC_NORSRAMInitStructure.FMC_WriteOperation = FMC_WriteOperation_Enable;
+ FMC_NORSRAMInitStructure.FMC_WaitSignal = FMC_WaitSignal_Disable;
+ FMC_NORSRAMInitStructure.FMC_ExtendedMode = FMC_ExtendedMode_Disable;
+ FMC_NORSRAMInitStructure.FMC_WriteBurst = FMC_WriteBurst_Disable;
+ FMC_NORSRAMInitStructure.FMC_ContinousClock = FMC_CClock_SyncOnly;
+ FMC_NORSRAMInitStructure.FMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
+ FMC_NORSRAMInitStructure.FMC_WriteTimingStruct = &NORSRAMTimingStructure;
+*/
+
+}
+#endif /* DATA_IN_ExtSRAM */
+
+#ifdef DATA_IN_ExtSDRAM
+/**
+ * @brief Setup the external memory controller.
+ * Called in startup_stm32f4xx.s before jump to main.
+ * This function configures the external SDRAM mounted on STM324x9I_EVAL board
+ * This SDRAM will be used as program data memory (including heap and stack).
+ * @param None
+ * @retval None
+ */
+void SystemInit_ExtMemCtl(void)
+{
+ register uint32_t tmpreg = 0, timeout = 0xFFFF;
+ register uint32_t index;
+
+ /* Enable GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface
+ clock */
+ RCC->AHB1ENR |= 0x000001FC;
+
+ /* Connect PCx pins to FMC Alternate function */
+ GPIOC->AFR[0] = 0x0000000c;
+ GPIOC->AFR[1] = 0x00007700;
+ /* Configure PCx pins in Alternate function mode */
+ GPIOC->MODER = 0x00a00002;
+ /* Configure PCx pins speed to 50 MHz */
+ GPIOC->OSPEEDR = 0x00a00002;
+ /* Configure PCx pins Output type to push-pull */
+ GPIOC->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PCx pins */
+ GPIOC->PUPDR = 0x00500000;
+
+ /* Connect PDx pins to FMC Alternate function */
+ GPIOD->AFR[0] = 0x000000CC;
+ GPIOD->AFR[1] = 0xCC000CCC;
+ /* Configure PDx pins in Alternate function mode */
+ GPIOD->MODER = 0xA02A000A;
+ /* Configure PDx pins speed to 50 MHz */
+ GPIOD->OSPEEDR = 0xA02A000A;
+ /* Configure PDx pins Output type to push-pull */
+ GPIOD->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PDx pins */
+ GPIOD->PUPDR = 0x00000000;
+
+ /* Connect PEx pins to FMC Alternate function */
+ GPIOE->AFR[0] = 0xC00000CC;
+ GPIOE->AFR[1] = 0xCCCCCCCC;
+ /* Configure PEx pins in Alternate function mode */
+ GPIOE->MODER = 0xAAAA800A;
+ /* Configure PEx pins speed to 50 MHz */
+ GPIOE->OSPEEDR = 0xAAAA800A;
+ /* Configure PEx pins Output type to push-pull */
+ GPIOE->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PEx pins */
+ GPIOE->PUPDR = 0x00000000;
+
+ /* Connect PFx pins to FMC Alternate function */
+ GPIOF->AFR[0] = 0xcccccccc;
+ GPIOF->AFR[1] = 0xcccccccc;
+ /* Configure PFx pins in Alternate function mode */
+ GPIOF->MODER = 0xAA800AAA;
+ /* Configure PFx pins speed to 50 MHz */
+ GPIOF->OSPEEDR = 0xAA800AAA;
+ /* Configure PFx pins Output type to push-pull */
+ GPIOF->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PFx pins */
+ GPIOF->PUPDR = 0x00000000;
+
+ /* Connect PGx pins to FMC Alternate function */
+ GPIOG->AFR[0] = 0xcccccccc;
+ GPIOG->AFR[1] = 0xcccccccc;
+ /* Configure PGx pins in Alternate function mode */
+ GPIOG->MODER = 0xaaaaaaaa;
+ /* Configure PGx pins speed to 50 MHz */
+ GPIOG->OSPEEDR = 0xaaaaaaaa;
+ /* Configure PGx pins Output type to push-pull */
+ GPIOG->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PGx pins */
+ GPIOG->PUPDR = 0x00000000;
+
+ /* Connect PHx pins to FMC Alternate function */
+ GPIOH->AFR[0] = 0x00C0CC00;
+ GPIOH->AFR[1] = 0xCCCCCCCC;
+ /* Configure PHx pins in Alternate function mode */
+ GPIOH->MODER = 0xAAAA08A0;
+ /* Configure PHx pins speed to 50 MHz */
+ GPIOH->OSPEEDR = 0xAAAA08A0;
+ /* Configure PHx pins Output type to push-pull */
+ GPIOH->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PHx pins */
+ GPIOH->PUPDR = 0x00000000;
+
+ /* Connect PIx pins to FMC Alternate function */
+ GPIOI->AFR[0] = 0xCCCCCCCC;
+ GPIOI->AFR[1] = 0x00000CC0;
+ /* Configure PIx pins in Alternate function mode */
+ GPIOI->MODER = 0x0028AAAA;
+ /* Configure PIx pins speed to 50 MHz */
+ GPIOI->OSPEEDR = 0x0028AAAA;
+ /* Configure PIx pins Output type to push-pull */
+ GPIOI->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PIx pins */
+ GPIOI->PUPDR = 0x00000000;
+
+/*-- FMC Configuration ------------------------------------------------------*/
+ /* Enable the FMC interface clock */
+ RCC->AHB3ENR |= 0x00000001;
+
+ /* Configure and enable SDRAM bank1 */
+ FMC_Bank5_6->SDCR[0] = 0x000039D0;
+ FMC_Bank5_6->SDTR[0] = 0x01115351;
+
+ /* SDRAM initialization sequence */
+ /* Clock enable command */
+ FMC_Bank5_6->SDCMR = 0x00000011;
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Delay */
+ for (index = 0; index<1000; index++);
+
+ /* PALL command */
+ FMC_Bank5_6->SDCMR = 0x00000012;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Auto refresh command */
+ FMC_Bank5_6->SDCMR = 0x00000073;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* MRD register program */
+ FMC_Bank5_6->SDCMR = 0x00046014;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Set refresh count */
+ tmpreg = FMC_Bank5_6->SDRTR;
+ FMC_Bank5_6->SDRTR = (tmpreg | (0x0000027C<<1));
+
+ /* Disable write protection */
+ tmpreg = FMC_Bank5_6->SDCR[0];
+ FMC_Bank5_6->SDCR[0] = (tmpreg & 0xFFFFFDFF);
+
+/*
+ Bank1_SDRAM is configured as follow:
+
+ FMC_SDRAMTimingInitStructure.FMC_LoadToActiveDelay = 2;
+ FMC_SDRAMTimingInitStructure.FMC_ExitSelfRefreshDelay = 6;
+ FMC_SDRAMTimingInitStructure.FMC_SelfRefreshTime = 4;
+ FMC_SDRAMTimingInitStructure.FMC_RowCycleDelay = 6;
+ FMC_SDRAMTimingInitStructure.FMC_WriteRecoveryTime = 2;
+ FMC_SDRAMTimingInitStructure.FMC_RPDelay = 2;
+ FMC_SDRAMTimingInitStructure.FMC_RCDDelay = 2;
+
+ FMC_SDRAMInitStructure.FMC_Bank = SDRAM_BANK;
+ FMC_SDRAMInitStructure.FMC_ColumnBitsNumber = FMC_ColumnBits_Number_8b;
+ FMC_SDRAMInitStructure.FMC_RowBitsNumber = FMC_RowBits_Number_11b;
+ FMC_SDRAMInitStructure.FMC_SDMemoryDataWidth = FMC_SDMemory_Width_16b;
+ FMC_SDRAMInitStructure.FMC_InternalBankNumber = FMC_InternalBank_Number_4;
+ FMC_SDRAMInitStructure.FMC_CASLatency = FMC_CAS_Latency_3;
+ FMC_SDRAMInitStructure.FMC_WriteProtection = FMC_Write_Protection_Disable;
+ FMC_SDRAMInitStructure.FMC_SDClockPeriod = FMC_SDClock_Period_2;
+ FMC_SDRAMInitStructure.FMC_ReadBurst = FMC_Read_Burst_disable;
+ FMC_SDRAMInitStructure.FMC_ReadPipeDelay = FMC_ReadPipe_Delay_1;
+ FMC_SDRAMInitStructure.FMC_SDRAMTimingStruct = &FMC_SDRAMTimingInitStructure;
+*/
+
+}
+#endif /* DATA_IN_ExtSDRAM */
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/src/main/target/REVO/system_stm32f4xx.h b/src/main/target/REVO/system_stm32f4xx.h
new file mode 100644
index 000000000..5e30ef818
--- /dev/null
+++ b/src/main/target/REVO/system_stm32f4xx.h
@@ -0,0 +1,105 @@
+/**
+ ******************************************************************************
+ * @file system_stm32f4xx.h
+ * @author MCD Application Team
+ * @version V1.6.1
+ * @date 21-October-2015
+ * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT 2015 STMicroelectronics
+ *
+ * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+ * You may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at:
+ *
+ * http://www.st.com/software_license_agreement_liberty_v2
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f4xx_system
+ * @{
+ */
+
+/**
+ * @brief Define to prevent recursive inclusion
+ */
+#ifndef __SYSTEM_STM32F4XX_H
+#define __SYSTEM_STM32F4XX_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/** @addtogroup STM32F4xx_System_Includes
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @addtogroup STM32F4xx_System_Exported_types
+ * @{
+ */
+
+extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
+
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Exported_Constants
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Exported_Functions
+ * @{
+ */
+
+extern void SystemInit(void);
+extern void SystemCoreClockUpdate(void);
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__SYSTEM_STM32F4XX_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/