diff --git a/Makefile b/Makefile old mode 100644 new mode 100755 index a7cd3433f..c4940a086 --- a/Makefile +++ b/Makefile @@ -38,7 +38,7 @@ FLASH_SIZE ?= FORKNAME = cleanflight -VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENWIIF1 ALIENWIIF3 +VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENWIIF1 ALIENWIIF3 COLIBRI_RACE # Valid targets for OP BootLoader support OPBL_VALID_TARGETS = CC3D @@ -49,7 +49,7 @@ ifeq ($(TARGET),$(filter $(TARGET),CJMCU)) FLASH_SIZE = 64 else ifeq ($(TARGET),$(filter $(TARGET),NAZE CC3D ALIENWIIF1 OLIMEXINO)) FLASH_SIZE = 128 -else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 SPARKY ALIENWIIF3)) +else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 SPARKY ALIENWIIF3 COLIBRI_RACE)) FLASH_SIZE = 256 else $(error FLASH_SIZE not configured for target) @@ -72,7 +72,7 @@ VPATH := $(SRC_DIR):$(SRC_DIR)/startup USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver USBPERIPH_SRC = $(notdir $(wildcard $(USBFS_DIR)/src/*.c)) -ifeq ($(TARGET),$(filter $(TARGET),STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 SPARKY ALIENWIIF3)) +ifeq ($(TARGET),$(filter $(TARGET),STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 SPARKY ALIENWIIF3 COLIBRI_RACE)) STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver @@ -510,6 +510,18 @@ CHEBUZZF3_SRC = \ $(HIGHEND_SRC) \ $(COMMON_SRC) +COLIBRI_RACE_SRC = \ + $(STM32F30x_COMMON_SRC) \ + drivers/display_ug2864hsweg01.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/barometer_ms5611.c \ + drivers/compass_ak8975.c \ + drivers/compass_hmc5883l.c \ + drivers/serial_usb_vcp.c \ + $(HIGHEND_SRC) \ + $(COMMON_SRC) \ + $(VCP_SRC) + SPARKY_SRC = \ $(STM32F30x_COMMON_SRC) \ drivers/display_ug2864hsweg01.c \ diff --git a/src/main/config/config.c b/src/main/config/config.c old mode 100644 new mode 100755 index 91f1ad949..6764ad4ab --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -361,7 +361,7 @@ static void resetConf(void) masterConfig.version = EEPROM_CONF_VERSION; masterConfig.mixerMode = MIXER_QUADX; featureClearAll(); -#if defined(CJMCU) || defined(SPARKY) +#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) featureSet(FEATURE_RX_PPM); #endif diff --git a/src/main/drivers/accgyro_spi_mpu6500.c b/src/main/drivers/accgyro_spi_mpu6500.c old mode 100644 new mode 100755 index f293d7104..e83c5d888 --- a/src/main/drivers/accgyro_spi_mpu6500.c +++ b/src/main/drivers/accgyro_spi_mpu6500.c @@ -94,11 +94,53 @@ static void mpu6500ReadRegister(uint8_t reg, uint8_t *data, int length) DISABLE_MPU6500; } +static void mpu6500SpiInit(void) +{ + static bool hardwareInitialised = false; + + if (hardwareInitialised) { + return; + } + +#ifdef STM32F303xC + RCC_AHBPeriphClockCmd(MPU6500_CS_GPIO_CLK_PERIPHERAL, ENABLE); + + GPIO_InitTypeDef GPIO_InitStructure; + GPIO_InitStructure.GPIO_Pin = MPU6500_CS_PIN; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + + GPIO_Init(MPU6500_CS_GPIO, &GPIO_InitStructure); +#endif + +#ifdef STM32F10X + RCC_APB2PeriphClockCmd(MPU6500_CS_GPIO_CLK_PERIPHERAL, ENABLE); + + gpio_config_t gpio; + // CS as output + gpio.mode = Mode_Out_PP; + gpio.pin = MPU6500_CS_PIN; + gpio.speed = Speed_50MHz; + gpioInit(MPU6500_CS_GPIO, &gpio); +#endif + + GPIO_SetBits(MPU6500_CS_GPIO, MPU6500_CS_PIN); + + spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_9MHZ_CLOCK_DIVIDER); + + hardwareInitialised = true; +} + static bool mpu6500Detect(void) { uint8_t tmp; + mpu6500SpiInit(); + mpu6500ReadRegister(MPU6500_RA_WHOAMI, &tmp, 1); + if (tmp != MPU6500_WHO_AM_I_CONST) return false; @@ -165,7 +207,6 @@ static void mpu6500AccRead(int16_t *accData) static void mpu6500GyroInit(void) { - #ifdef NAZE gpio_config_t gpio; // MPU_INT output on rev5 hardware (PC13). rev4 was on PB13, conflicts with SPI devices diff --git a/src/main/drivers/accgyro_spi_mpu6500.h b/src/main/drivers/accgyro_spi_mpu6500.h old mode 100644 new mode 100755 diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index f2b0cb244..dd46b40a8 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -34,17 +34,18 @@ static volatile uint16_t spi3ErrorCount = 0; #ifdef USE_SPI_DEVICE_1 +#ifndef SPI1_GPIO #define SPI1_GPIO GPIOA -#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB +#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOA +#define SPI1_NSS_PIN GPIO_Pin_4 +#define SPI1_NSS_PIN_SOURCE GPIO_PinSource4 #define SPI1_SCK_PIN GPIO_Pin_5 #define SPI1_SCK_PIN_SOURCE GPIO_PinSource5 -#define SPI1_SCK_CLK RCC_AHBPeriph_GPIOA #define SPI1_MISO_PIN GPIO_Pin_6 #define SPI1_MISO_PIN_SOURCE GPIO_PinSource6 -#define SPI1_MISO_CLK RCC_AHBPeriph_GPIOA #define SPI1_MOSI_PIN GPIO_Pin_7 #define SPI1_MOSI_PIN_SOURCE GPIO_PinSource7 -#define SPI1_MOSI_CLK RCC_AHBPeriph_GPIOA +#endif void initSpi1(void) { @@ -70,32 +71,46 @@ void initSpi1(void) GPIO_PinAFConfig(SPI1_GPIO, SPI1_SCK_PIN_SOURCE, GPIO_AF_5); GPIO_PinAFConfig(SPI1_GPIO, SPI1_MISO_PIN_SOURCE, GPIO_AF_5); GPIO_PinAFConfig(SPI1_GPIO, SPI1_MOSI_PIN_SOURCE, GPIO_AF_5); - +#ifdef SPI1_NSS_PIN_SOURCE + GPIO_PinAFConfig(SPI1_GPIO, SPI1_NSS_PIN_SOURCE, GPIO_AF_5); +#endif // Init pins GPIO_InitStructure.GPIO_Pin = SPI1_SCK_PIN | SPI1_MISO_PIN | SPI1_MOSI_PIN; GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + GPIO_Init(SPI1_GPIO, &GPIO_InitStructure); + +#ifdef SPI1_NSS_PIN + GPIO_InitStructure.GPIO_Pin = SPI1_NSS_PIN; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; GPIO_Init(SPI1_GPIO, &GPIO_InitStructure); #endif +#endif + #ifdef STM32F10X gpio_config_t gpio; // MOSI + SCK as output gpio.mode = Mode_AF_PP; - gpio.pin = Pin_7 | Pin_5; + gpio.pin = SPI1_MOSI_PIN | SPI1_SCK_PIN; gpio.speed = Speed_50MHz; gpioInit(GPIOA, &gpio); // MISO as input - gpio.pin = Pin_6; + gpio.pin = SPI1_MISO_PIN; gpio.mode = Mode_IN_FLOATING; gpioInit(GPIOA, &gpio); +#ifdef SPI1_NSS_PIN // NSS as gpio slave select - gpio.pin = Pin_4; + gpio.pin = SPI1_NSS_PIN; gpio.mode = Mode_Out_PP; gpioInit(GPIOA, &gpio); +#endif #endif // Init SPI hardware @@ -160,6 +175,9 @@ void initSpi2(void) GPIO_PinAFConfig(SPI2_GPIO, SPI2_SCK_PIN_SOURCE, GPIO_AF_5); GPIO_PinAFConfig(SPI2_GPIO, SPI2_MISO_PIN_SOURCE, GPIO_AF_5); GPIO_PinAFConfig(SPI2_GPIO, SPI2_MOSI_PIN_SOURCE, GPIO_AF_5); +#ifdef SPI2_NSS_PIN_SOURCE + GPIO_PinAFConfig(SPI2_GPIO, SPI2_NSS_PIN_SOURCE, GPIO_AF_5); +#endif GPIO_InitStructure.GPIO_Pin = SPI2_SCK_PIN | SPI2_MISO_PIN | SPI2_MOSI_PIN; GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; @@ -168,6 +186,7 @@ void initSpi2(void) GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; GPIO_Init(SPI2_GPIO, &GPIO_InitStructure); +#ifdef SPI2_NSS_PIN GPIO_InitStructure.GPIO_Pin = SPI2_NSS_PIN; GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; @@ -175,6 +194,7 @@ void initSpi2(void) GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; GPIO_Init(SPI2_GPIO, &GPIO_InitStructure); +#endif #endif @@ -191,10 +211,12 @@ void initSpi2(void) gpio.mode = Mode_IN_FLOATING; gpioInit(SPI2_GPIO, &gpio); +#ifdef SPI2_NSS_PIN // NSS as gpio slave select gpio.pin = SPI2_NSS_PIN; gpio.mode = Mode_Out_PP; gpioInit(SPI2_GPIO, &gpio); +#endif #endif // Init SPI2 hardware diff --git a/src/main/drivers/light_led_stm32f30x.c b/src/main/drivers/light_led_stm32f30x.c index 0e6d47a1d..cce6a0650 100644 --- a/src/main/drivers/light_led_stm32f30x.c +++ b/src/main/drivers/light_led_stm32f30x.c @@ -45,6 +45,12 @@ void ledInit(void) { .gpio = LED1_GPIO, .cfg = { LED1_PIN, Mode_Out_PP, Speed_2MHz } + }, +#endif +#ifdef LED2 + { + .gpio = LED2_GPIO, + .cfg = { LED2_PIN, Mode_Out_PP, Speed_2MHz } } #endif }; @@ -57,9 +63,13 @@ void ledInit(void) #ifdef LED1 RCC_AHBPeriphClockCmd(LED1_PERIPHERAL, ENABLE); #endif +#ifdef LED2 + RCC_AHBPeriphClockCmd(LED2_PERIPHERAL, ENABLE); +#endif LED0_OFF; LED1_OFF; + LED2_OFF; for (i = 0; i < gpio_count; i++) { gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg); diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c old mode 100644 new mode 100755 index aa6c6109a..9ef45a964 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -241,6 +241,48 @@ static const uint16_t airPWM[] = { }; #endif +#ifdef COLIBRI_RACE +static const uint16_t multiPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + 0xFFFF +}; + +static const uint16_t multiPWM[] = { + // TODO + 0xFFFF +}; + +static const uint16_t airPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + 0xFFFF +}; + +static const uint16_t airPWM[] = { + // TODO + 0xFFFF +}; +#endif + #if defined(SPARKY) || defined(ALIENWIIF3) static const uint16_t multiPPM[] = { PWM11 | (MAP_TO_PPM_INPUT << 8), // PPM input @@ -478,6 +520,12 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) type = MAP_TO_SERVO_OUTPUT; #endif +#if defined(COLIBRI_RACE) + // remap PWM1+2 as servos + if ((timerIndex == PWM6 || timerIndex == PWM7 || timerIndex == PWM8 || timerIndex == PWM9) && timerHardwarePtr->tim == TIM2) + type = MAP_TO_SERVO_OUTPUT; +#endif + #if defined(SPARKY) // remap PWM1+2 as servos if ((timerIndex == PWM1 || timerIndex == PWM2) && timerHardwarePtr->tim == TIM15) diff --git a/src/main/drivers/pwm_rx.c b/src/main/drivers/pwm_rx.c index ba59bd865..90dd28a0b 100644 --- a/src/main/drivers/pwm_rx.c +++ b/src/main/drivers/pwm_rx.c @@ -359,4 +359,3 @@ uint16_t pwmRead(uint8_t channel) { return captures[channel]; } - diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c old mode 100644 new mode 100755 index a2c84663f..bf9d839e6 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -115,6 +115,32 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { #endif +#ifdef COLIBRI_RACE +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_6}, // PWM1 - PA8 + + { TIM3, GPIOC, Pin_6, TIM_Channel_1, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2}, // PWM2 - PC6 + { TIM3, GPIOC, Pin_7, TIM_Channel_2, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_2}, // PWM3 - PC7 + { TIM3, GPIOC, Pin_8, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2}, // PMW4 - PC8 + { TIM3, GPIOC, Pin_9, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2}, // PWM5 - PC9 + + { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1}, // PWM6 - PA0 + { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // PWM7 - PA1 + { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_1}, // PWM8 - PA2 + { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_1}, // PWM9 - PA3 + + { TIM15, GPIOB, Pin_14, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource14, GPIO_AF_1}, // PWM10 - PB14 + { TIM15, GPIOB, Pin_15, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource15, GPIO_AF_1}, // PWM11 - PB15 +}; + +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15)) + +#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3) +#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15) +#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOC) + +#endif + #ifdef CHEBUZZF3 const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // INPUTS CH1-8 diff --git a/src/main/io/gps.c b/src/main/io/gps.c old mode 100644 new mode 100755 index da701f751..c5ebe3b99 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -238,7 +238,7 @@ void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig) portMode_t mode = MODE_RXTX; // only RX is needed for NMEA-style GPS if (gpsConfig->provider == GPS_NMEA) - mode &= ~MODE_TX; + mode &= ~MODE_TX; // no callback - buffer will be consumed in gpsThread() gpsPort = openSerialPort(gpsPortConfig->identifier, FUNCTION_GPS, NULL, gpsInitData[gpsData.baudrateIndex].baudrateIndex, mode, SERIAL_NOT_INVERTED); diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c old mode 100644 new mode 100755 index 8400b1f1a..e028bc0dd --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -36,6 +36,7 @@ #include "drivers/accgyro_l3gd20.h" #include "drivers/accgyro_lsm303dlhc.h" +#include "drivers/bus_spi.h" #include "drivers/accgyro_spi_mpu6000.h" #include "drivers/accgyro_spi_mpu6500.h" @@ -74,6 +75,7 @@ extern acc_t acc; uint8_t detectedSensors[MAX_SENSORS_TO_DETECT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE }; + const mpu6050Config_t *selectMPU6050Config(void) { #ifdef NAZE @@ -225,6 +227,9 @@ bool detectGyro(uint16_t gyroLpf) case GYRO_SPI_MPU6500: #ifdef USE_GYRO_SPI_MPU6500 +#ifdef USE_HARDWARE_REVISION_DETECTION + spiBusInit(); +#endif #ifdef NAZE if (hardwareRevision == NAZE32_SP && mpu6500SpiGyroDetect(&gyro, gyroLpf)) { #ifdef GYRO_SPI_MPU6500_ALIGN diff --git a/src/main/target/CJMCU/hardware_revision.c b/src/main/target/CJMCU/hardware_revision.c old mode 100644 new mode 100755 index f424ee2af..88cbbae1e --- a/src/main/target/CJMCU/hardware_revision.c +++ b/src/main/target/CJMCU/hardware_revision.c @@ -51,3 +51,7 @@ void detectHardwareRevision(void) void updateHardwareRevision(void) { } + +void spiBusInit(void) +{ +} diff --git a/src/main/target/CJMCU/hardware_revision.h b/src/main/target/CJMCU/hardware_revision.h old mode 100644 new mode 100755 index 0b5c25527..4eee9078f --- a/src/main/target/CJMCU/hardware_revision.h +++ b/src/main/target/CJMCU/hardware_revision.h @@ -25,3 +25,5 @@ extern uint8_t hardwareRevision; void updateHardwareRevision(void); void detectHardwareRevision(void); + +void spiBusInit(void); diff --git a/src/main/target/COLIBRI_RACE/system_stm32f30x.c b/src/main/target/COLIBRI_RACE/system_stm32f30x.c new file mode 100755 index 000000000..fca696982 --- /dev/null +++ b/src/main/target/COLIBRI_RACE/system_stm32f30x.c @@ -0,0 +1,372 @@ +/** + ****************************************************************************** + * @file system_stm32f30x.c + * @author MCD Application Team + * @version V1.1.1 + * @date 28-March-2014 + * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File. + * This file contains the system clock configuration for STM32F30x devices, + * and is generated by the clock configuration tool + * stm32f30x_Clock_Configuration_V1.0.0.xls + * + * 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_stm32f30x.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 (8 MHz) is used as system clock source. + * Then SystemInit() function is called, in "startup_stm32f30x.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 8MHz, refer to "HSE_VALUE" define + * in "stm32f30x.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 STM32F30x device + *----------------------------------------------------------------------------- + * System Clock source | PLL (HSE) + *----------------------------------------------------------------------------- + * SYSCLK(Hz) | 72000000 + *----------------------------------------------------------------------------- + * HCLK(Hz) | 72000000 + *----------------------------------------------------------------------------- + * AHB Prescaler | 1 + *----------------------------------------------------------------------------- + * APB2 Prescaler | 2 + *----------------------------------------------------------------------------- + * APB1 Prescaler | 2 + *----------------------------------------------------------------------------- + * HSE Frequency(Hz) | 8000000 + *---------------------------------------------------------------------------- + * PLLMUL | 9 + *----------------------------------------------------------------------------- + * PREDIV | 1 + *----------------------------------------------------------------------------- + * USB Clock | ENABLE + *----------------------------------------------------------------------------- + * Flash Latency(WS) | 2 + *----------------------------------------------------------------------------- + * Prefetch Buffer | ON + *----------------------------------------------------------------------------- + *============================================================================= + ****************************************************************************** + * @attention + * + *