mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 13:25:30 +03:00
MASSIVEF3 - Add new target.
This commit is contained in:
parent
a199685d83
commit
6beec3c6e9
6 changed files with 675 additions and 4 deletions
20
Makefile
20
Makefile
|
@ -35,7 +35,7 @@ SERIAL_DEVICE ?= /dev/ttyUSB0
|
||||||
|
|
||||||
FORKNAME = cleanflight
|
FORKNAME = cleanflight
|
||||||
|
|
||||||
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC
|
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC MASSIVEF3
|
||||||
|
|
||||||
# Valid targets for OP BootLoader support
|
# Valid targets for OP BootLoader support
|
||||||
OPBL_VALID_TARGETS = CC3D
|
OPBL_VALID_TARGETS = CC3D
|
||||||
|
@ -53,7 +53,7 @@ INCLUDE_DIRS = $(SRC_DIR)
|
||||||
# Search path for sources
|
# Search path for sources
|
||||||
VPATH := $(SRC_DIR):$(SRC_DIR)/startup
|
VPATH := $(SRC_DIR):$(SRC_DIR)/startup
|
||||||
|
|
||||||
ifeq ($(TARGET),$(filter $(TARGET),STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO))
|
ifeq ($(TARGET),$(filter $(TARGET),STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO MASSIVEF3))
|
||||||
|
|
||||||
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver
|
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver
|
||||||
USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver
|
USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver
|
||||||
|
@ -81,7 +81,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||||
$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x \
|
$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x \
|
||||||
$(ROOT)/src/main/vcp
|
$(ROOT)/src/main/vcp
|
||||||
|
|
||||||
LD_SCRIPT = $(ROOT)/stm32_flash_f303.ld
|
LD_SCRIPT = $(ROOT)/stm32_flash_f303_256k.ld
|
||||||
|
|
||||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
|
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
|
||||||
DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303
|
DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303
|
||||||
|
@ -91,6 +91,11 @@ ifeq ($(TARGET),CHEBUZZF3)
|
||||||
TARGET_FLAGS := $(TARGET_FLAGS) -DSTM32F3DISCOVERY
|
TARGET_FLAGS := $(TARGET_FLAGS) -DSTM32F3DISCOVERY
|
||||||
endif
|
endif
|
||||||
|
|
||||||
|
ifeq ($(TARGET),MASSIVEF3)
|
||||||
|
# MASSIVEF3 is a VARIANT of STM32F3DISCOVERY
|
||||||
|
TARGET_FLAGS := $(TARGET_FLAGS) -DSTM32F3DISCOVERY
|
||||||
|
endif
|
||||||
|
|
||||||
|
|
||||||
else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC))
|
else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC))
|
||||||
|
|
||||||
|
@ -394,6 +399,15 @@ CHEBUZZF3_SRC = $(STM32F3DISCOVERY_SRC) \
|
||||||
$(HIGHEND_SRC) \
|
$(HIGHEND_SRC) \
|
||||||
$(COMMON_SRC)
|
$(COMMON_SRC)
|
||||||
|
|
||||||
|
MASSIVEF3_SRC = $(STM32F3DISCOVERY_SRC) \
|
||||||
|
$(HIGHEND_SRC) \
|
||||||
|
$(COMMON_SRC)
|
||||||
|
|
||||||
|
ifeq ($(TARGET),MASSIVEF3)
|
||||||
|
LD_SCRIPT = $(ROOT)/stm32_flash_f303_128k.ld
|
||||||
|
endif
|
||||||
|
|
||||||
|
|
||||||
# Search path and source files for the ST stdperiph library
|
# Search path and source files for the ST stdperiph library
|
||||||
VPATH := $(VPATH):$(STDPERIPH_DIR)/src
|
VPATH := $(VPATH):$(STDPERIPH_DIR)/src
|
||||||
|
|
||||||
|
|
|
@ -69,7 +69,7 @@ enum {
|
||||||
MAP_TO_SERVO_OUTPUT,
|
MAP_TO_SERVO_OUTPUT,
|
||||||
};
|
};
|
||||||
|
|
||||||
#if defined(NAZE) || defined(OLIMEXINO) || defined(NAZE32PRO) || defined(STM32F3DISCOVERY) || defined(EUSTM32F103RC)
|
#if defined(NAZE) || defined(OLIMEXINO) || defined(NAZE32PRO) || defined(STM32F3DISCOVERY) || defined(EUSTM32F103RC) || defined(MASSIVEF3)
|
||||||
static const uint16_t multiPPM[] = {
|
static const uint16_t multiPPM[] = {
|
||||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||||
|
|
372
src/main/target/MASSIVEF3/system_stm32f30x.c
Normal file
372
src/main/target/MASSIVEF3/system_stm32f30x.c
Normal file
|
@ -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) | 12000000
|
||||||
|
*----------------------------------------------------------------------------
|
||||||
|
* PLLMUL | 6
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* PREDIV | 1
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* USB Clock | ENABLE
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* Flash Latency(WS) | 2
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* Prefetch Buffer | ON
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
*=============================================================================
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* <h2><center>© COPYRIGHT 2014 STMicroelectronics</center></h2>
|
||||||
|
*
|
||||||
|
* 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 stm32f30x_system
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Private_Includes
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "stm32f30x.h"
|
||||||
|
|
||||||
|
uint32_t hse_value = HSE_VALUE;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Private typedef -----------------------------------------------------------*/
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Private_Defines
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
/*!< Uncomment the following line if you need to relocate your vector Table in
|
||||||
|
Internal SRAM. */
|
||||||
|
/* #define VECT_TAB_SRAM */
|
||||||
|
#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
|
||||||
|
This value must be a multiple of 0x200. */
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Private macro -------------------------------------------------------------*/
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Private_Variables
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
uint32_t SystemCoreClock = 72000000;
|
||||||
|
|
||||||
|
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Private_FunctionPrototypes
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
void SetSysClock(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_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 &= 0xF87FC00C;
|
||||||
|
|
||||||
|
/* Reset HSEON, CSSON and PLLON bits */
|
||||||
|
RCC->CR &= (uint32_t)0xFEF6FFFF;
|
||||||
|
|
||||||
|
/* Reset HSEBYP bit */
|
||||||
|
RCC->CR &= (uint32_t)0xFFFBFFFF;
|
||||||
|
|
||||||
|
/* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */
|
||||||
|
RCC->CFGR &= (uint32_t)0xFF80FFFF;
|
||||||
|
|
||||||
|
/* Reset PREDIV1[3:0] bits */
|
||||||
|
RCC->CFGR2 &= (uint32_t)0xFFFFFFF0;
|
||||||
|
|
||||||
|
/* Reset USARTSW[1:0], I2CSW and TIMs bits */
|
||||||
|
RCC->CFGR3 &= (uint32_t)0xFF00FCCC;
|
||||||
|
|
||||||
|
/* Disable all interrupts */
|
||||||
|
RCC->CIR = 0x00000000;
|
||||||
|
|
||||||
|
/* Configure the System clock source, PLL Multiplier and Divider factors,
|
||||||
|
AHB/APBx prescalers and Flash settings ----------------------------------*/
|
||||||
|
//SetSysClock(); // called from main()
|
||||||
|
|
||||||
|
#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 stm32f30x.h file (default value
|
||||||
|
* 8 MHz) but the real value may vary depending on the variations
|
||||||
|
* in voltage and temperature.
|
||||||
|
*
|
||||||
|
* (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value
|
||||||
|
* 8 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, pllmull = 0, pllsource = 0, prediv1factor = 0;
|
||||||
|
|
||||||
|
/* Get SYSCLK source -------------------------------------------------------*/
|
||||||
|
tmp = RCC->CFGR & RCC_CFGR_SWS;
|
||||||
|
|
||||||
|
switch (tmp)
|
||||||
|
{
|
||||||
|
case 0x00: /* HSI used as system clock */
|
||||||
|
SystemCoreClock = HSI_VALUE;
|
||||||
|
break;
|
||||||
|
case 0x04: /* HSE used as system clock */
|
||||||
|
SystemCoreClock = HSE_VALUE;
|
||||||
|
break;
|
||||||
|
case 0x08: /* PLL used as system clock */
|
||||||
|
/* Get PLL clock source and multiplication factor ----------------------*/
|
||||||
|
pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
|
||||||
|
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
|
||||||
|
pllmull = ( pllmull >> 18) + 2;
|
||||||
|
|
||||||
|
if (pllsource == 0x00)
|
||||||
|
{
|
||||||
|
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
|
||||||
|
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
|
||||||
|
/* HSE oscillator clock selected as PREDIV1 clock entry */
|
||||||
|
SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
default: /* HSI used as system clock */
|
||||||
|
SystemCoreClock = HSI_VALUE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
/* Compute HCLK clock frequency ----------------*/
|
||||||
|
/* Get HCLK prescaler */
|
||||||
|
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
|
||||||
|
/* HCLK clock 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)
|
||||||
|
{
|
||||||
|
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||||
|
|
||||||
|
/******************************************************************************/
|
||||||
|
/* PLL (clocked by HSE) used as System clock source */
|
||||||
|
/******************************************************************************/
|
||||||
|
|
||||||
|
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------*/
|
||||||
|
/* 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)
|
||||||
|
{
|
||||||
|
/* Enable Prefetch Buffer and set Flash Latency */
|
||||||
|
FLASH->ACR = FLASH_ACR_PRFTBE | (uint32_t)FLASH_ACR_LATENCY_1;
|
||||||
|
|
||||||
|
/* HCLK = SYSCLK / 1 */
|
||||||
|
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
|
||||||
|
|
||||||
|
/* PCLK2 = HCLK / 1 */
|
||||||
|
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
|
||||||
|
|
||||||
|
/* PCLK1 = HCLK / 2 */
|
||||||
|
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
|
||||||
|
|
||||||
|
/* PLL configuration */
|
||||||
|
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
|
||||||
|
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL9);
|
||||||
|
|
||||||
|
/* Enable PLL */
|
||||||
|
RCC->CR |= RCC_CR_PLLON;
|
||||||
|
|
||||||
|
/* Wait till PLL is ready */
|
||||||
|
while((RCC->CR & RCC_CR_PLLRDY) == 0)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Select PLL as system clock source */
|
||||||
|
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
|
||||||
|
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
|
||||||
|
|
||||||
|
/* Wait till PLL is used as system clock source */
|
||||||
|
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)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 */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||||
|
|
76
src/main/target/MASSIVEF3/system_stm32f30x.h
Normal file
76
src/main/target/MASSIVEF3/system_stm32f30x.h
Normal file
|
@ -0,0 +1,76 @@
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* @file system_stm32f30x.h
|
||||||
|
* @author MCD Application Team
|
||||||
|
* @version V1.1.1
|
||||||
|
* @date 28-March-2014
|
||||||
|
* @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices.
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* <h2><center>© COPYRIGHT 2014 STMicroelectronics</center></h2>
|
||||||
|
*
|
||||||
|
* 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 stm32f30x_system
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Define to prevent recursive inclusion
|
||||||
|
*/
|
||||||
|
#ifndef __SYSTEM_STM32F30X_H
|
||||||
|
#define __SYSTEM_STM32F30X_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Exported types ------------------------------------------------------------*/
|
||||||
|
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
|
||||||
|
/* Exported constants --------------------------------------------------------*/
|
||||||
|
/* Exported macro ------------------------------------------------------------*/
|
||||||
|
/* Exported functions ------------------------------------------------------- */
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Exported_Functions
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
extern void SystemInit(void);
|
||||||
|
extern void SystemCoreClockUpdate(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /*__SYSTEM_STM32F30X_H */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
59
src/main/target/MASSIVEF3/target.h
Normal file
59
src/main/target/MASSIVEF3/target.h
Normal file
|
@ -0,0 +1,59 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#define LED0_GPIO GPIOE
|
||||||
|
#define LED0_PIN Pin_8|Pin_12 // Blue LEDs - PE8/PE12
|
||||||
|
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||||
|
#define LED0_INVERTED
|
||||||
|
#define LED1_GPIO GPIOE
|
||||||
|
#define LED1_PIN Pin_10|Pin_14 // Orange LEDs - PE10/PE14
|
||||||
|
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||||
|
#define LED1_INVERTED
|
||||||
|
|
||||||
|
#define BEEP_GPIO GPIOE
|
||||||
|
#define BEEP_PIN Pin_9|Pin_13 // Red LEDs - PE9/PE13
|
||||||
|
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||||
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
|
||||||
|
#define BEEPER_INVERTED
|
||||||
|
#define BARO_GPIO GPIOC
|
||||||
|
#define BARO_PIN Pin_13
|
||||||
|
|
||||||
|
#define GYRO
|
||||||
|
#define ACC
|
||||||
|
#define BEEPER
|
||||||
|
#define LED0
|
||||||
|
#define LED1
|
||||||
|
|
||||||
|
#define USE_VCP
|
||||||
|
#define USE_USART1
|
||||||
|
#define USE_USART2
|
||||||
|
#define SERIAL_PORT_COUNT 3
|
||||||
|
|
||||||
|
#define USE_I2C
|
||||||
|
#define I2C_DEVICE (I2CDEV_1)
|
||||||
|
|
||||||
|
#define SENSORS_SET (SENSOR_ACC)
|
||||||
|
|
||||||
|
#define GPS
|
||||||
|
#define LED_STRIP
|
||||||
|
#define TELEMETRY
|
||||||
|
#define SERIAL_RX
|
||||||
|
#define AUTOTUNE
|
150
stm32_flash_f303_128k.ld
Normal file
150
stm32_flash_f303_128k.ld
Normal file
|
@ -0,0 +1,150 @@
|
||||||
|
/*
|
||||||
|
*****************************************************************************
|
||||||
|
**
|
||||||
|
** File : stm32_flash.ld
|
||||||
|
**
|
||||||
|
** Abstract : Linker script for STM32F30x Device with
|
||||||
|
** 128KByte FLASH and 40KByte RAM
|
||||||
|
**
|
||||||
|
*****************************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Entry Point */
|
||||||
|
ENTRY(Reset_Handler)
|
||||||
|
|
||||||
|
/* Highest address of the user mode stack */
|
||||||
|
_estack = 0x2000A000; /* end of 40K RAM */
|
||||||
|
|
||||||
|
/* Generate a link error if heap and stack don't fit into RAM */
|
||||||
|
_Min_Heap_Size = 0; /* required amount of heap */
|
||||||
|
_Min_Stack_Size = 0x400; /* required amount of stack */
|
||||||
|
|
||||||
|
/* Specify the memory areas */
|
||||||
|
MEMORY
|
||||||
|
{
|
||||||
|
FLASH (rx) : ORIGIN = 0x04000000, LENGTH = 126K /* last 2kb used for config storage */
|
||||||
|
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 40K
|
||||||
|
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Define output sections */
|
||||||
|
SECTIONS
|
||||||
|
{
|
||||||
|
/* The startup code goes first into FLASH */
|
||||||
|
.isr_vector :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
KEEP(*(.isr_vector)) /* Startup code */
|
||||||
|
. = ALIGN(4);
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
/* The program code and other data goes into FLASH */
|
||||||
|
.text :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
*(.text) /* .text sections (code) */
|
||||||
|
*(.text*) /* .text* sections (code) */
|
||||||
|
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||||
|
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||||
|
*(.glue_7) /* glue arm to thumb code */
|
||||||
|
*(.glue_7t) /* glue thumb to arm code */
|
||||||
|
*(.eh_frame)
|
||||||
|
|
||||||
|
KEEP (*(.init))
|
||||||
|
KEEP (*(.fini))
|
||||||
|
|
||||||
|
. = ALIGN(4);
|
||||||
|
_etext = .; /* define a global symbols at end of code */
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
|
||||||
|
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
||||||
|
.ARM : {
|
||||||
|
__exidx_start = .;
|
||||||
|
*(.ARM.exidx*)
|
||||||
|
__exidx_end = .;
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
.preinit_array :
|
||||||
|
{
|
||||||
|
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||||
|
KEEP (*(.preinit_array*))
|
||||||
|
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||||
|
} >FLASH
|
||||||
|
.init_array :
|
||||||
|
{
|
||||||
|
PROVIDE_HIDDEN (__init_array_start = .);
|
||||||
|
KEEP (*(SORT(.init_array.*)))
|
||||||
|
KEEP (*(.init_array*))
|
||||||
|
PROVIDE_HIDDEN (__init_array_end = .);
|
||||||
|
} >FLASH
|
||||||
|
.fini_array :
|
||||||
|
{
|
||||||
|
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||||
|
KEEP (*(.fini_array*))
|
||||||
|
KEEP (*(SORT(.fini_array.*)))
|
||||||
|
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
/* used by the startup to initialize data */
|
||||||
|
_sidata = .;
|
||||||
|
|
||||||
|
/* Initialized data sections goes into RAM, load LMA copy after code */
|
||||||
|
.data :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
_sdata = .; /* create a global symbol at data start */
|
||||||
|
*(.data) /* .data sections */
|
||||||
|
*(.data*) /* .data* sections */
|
||||||
|
|
||||||
|
. = ALIGN(4);
|
||||||
|
_edata = .; /* define a global symbol at data end */
|
||||||
|
} >RAM AT> FLASH
|
||||||
|
|
||||||
|
/* Uninitialized data section */
|
||||||
|
. = ALIGN(4);
|
||||||
|
.bss :
|
||||||
|
{
|
||||||
|
/* This is used by the startup in order to initialize the .bss secion */
|
||||||
|
_sbss = .; /* define a global symbol at bss start */
|
||||||
|
__bss_start__ = _sbss;
|
||||||
|
*(.bss)
|
||||||
|
*(.bss*)
|
||||||
|
*(COMMON)
|
||||||
|
|
||||||
|
. = ALIGN(4);
|
||||||
|
_ebss = .; /* define a global symbol at bss end */
|
||||||
|
__bss_end__ = _ebss;
|
||||||
|
} >RAM
|
||||||
|
|
||||||
|
/* User_heap_stack section, used to check that there is enough RAM left */
|
||||||
|
._user_heap_stack :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
PROVIDE ( end = . );
|
||||||
|
PROVIDE ( _end = . );
|
||||||
|
. = . + _Min_Heap_Size;
|
||||||
|
. = . + _Min_Stack_Size;
|
||||||
|
. = ALIGN(4);
|
||||||
|
} >RAM
|
||||||
|
|
||||||
|
/* MEMORY_bank1 section, code must be located here explicitly */
|
||||||
|
/* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
|
||||||
|
.memory_b1_text :
|
||||||
|
{
|
||||||
|
*(.mb1text) /* .mb1text sections (code) */
|
||||||
|
*(.mb1text*) /* .mb1text* sections (code) */
|
||||||
|
*(.mb1rodata) /* read-only data (constants) */
|
||||||
|
*(.mb1rodata*)
|
||||||
|
} >MEMORY_B1
|
||||||
|
|
||||||
|
/* Remove information from the standard libraries */
|
||||||
|
/DISCARD/ :
|
||||||
|
{
|
||||||
|
libc.a ( * )
|
||||||
|
libm.a ( * )
|
||||||
|
libgcc.a ( * )
|
||||||
|
}
|
||||||
|
|
||||||
|
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||||
|
}
|
Loading…
Add table
Add a link
Reference in a new issue