diff --git a/Makefile b/Makefile index 38f32aef16..8d26455a63 100644 --- a/Makefile +++ b/Makefile @@ -32,7 +32,7 @@ SERIAL_DEVICE ?= /dev/ttyUSB0 FORKNAME = cleanflight -VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU +VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC # Working directories ROOT = $(dir $(lastword $(MAKEFILE_LIST))) @@ -76,7 +76,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \ LD_SCRIPT = $(ROOT)/stm32_flash_f303.ld 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 +DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303 TARGET_FLAGS = -D$(TARGET) ifeq ($(TARGET),CHEBUZZF3) # CHEBUZZ is a VARIANT of STM32F3DISCOVERY @@ -84,6 +84,31 @@ TARGET_FLAGS := $(TARGET_FLAGS) -DSTM32F3DISCOVERY endif +else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC)) + + +STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver + +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + +LD_SCRIPT = $(ROOT)/stm32_flash_f103_256k.ld + +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 +TARGET_FLAGS = -D$(TARGET) -pedantic +DEVICE_FLAGS = -DSTM32F10X_HD -DSTM32F10X + +DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC) + else STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver @@ -104,7 +129,7 @@ LD_SCRIPT = $(ROOT)/stm32_flash_f103_128k.ld ARCH_FLAGS = -mthumb -mcpu=cortex-m3 TARGET_FLAGS = -D$(TARGET) -pedantic -DEVICE_FLAGS = -DSTM32F10X_MD +DEVICE_FLAGS = -DSTM32F10X_MD -DSTM32F10X DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC) @@ -202,6 +227,31 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \ $(HIGHEND_SRC) \ $(COMMON_SRC) +EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \ + drivers/accgyro_mpu6050.c \ + drivers/adc.c \ + drivers/adc_stm32f10x.c \ + drivers/barometer_bmp085.c \ + drivers/bus_i2c_stm32f10x.c \ + drivers/bus_spi.c \ + drivers/compass_hmc5883l.c \ + drivers/gpio_stm32f10x.c \ + drivers/light_led_stm32f10x.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f10x.c \ + drivers/pwm_mapping.c \ + drivers/pwm_output.c \ + drivers/pwm_rx.c \ + drivers/serial_softserial.c \ + drivers/serial_uart.c \ + drivers/serial_uart_stm32f10x.c \ + drivers/sonar_hcsr04.c \ + drivers/sound_beeper_stm32f10x.c \ + drivers/system_stm32f10x.c \ + drivers/timer.c \ + $(HIGHEND_SRC) \ + $(COMMON_SRC) + OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \ drivers/accgyro_mpu6050.c \ drivers/adc.c \ diff --git a/src/main/config/config.c b/src/main/config/config.c index f3b40f0b32..9316d39f7a 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -75,11 +75,20 @@ void mixerUseConfigs(servoParam_t *servoConfToUse, flight3DConfig_t *flight3DCon #define FLASH_PAGE_SIZE ((uint16_t)0x800) #endif -#ifndef FLASH_PAGE_COUNT +#ifdef STM32F10X_MD #define FLASH_PAGE_COUNT 128 #define FLASH_PAGE_SIZE ((uint16_t)0x400) #endif +#ifdef STM32F10X_HD +#define FLASH_PAGE_COUNT 128 +#define FLASH_PAGE_SIZE ((uint16_t)0x800) +#endif + +#ifndef FLASH_PAGE_COUNT +#error "Flash page count not defined for target." +#endif + // use the last flash pages for storage static uint32_t flashWriteAddress = (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG)); @@ -465,14 +474,14 @@ void validateAndFixConfig(void) } if (feature(FEATURE_CURRENT_METER)) { -#if defined(STM32F10X_MD) +#if defined(STM32F10X) // rssi adc needs the same ports featureClear(FEATURE_RSSI_ADC); // current meter needs the same ports featureClear(FEATURE_CURRENT_METER); #endif -#if defined(STM32F10X_MD) || defined(CHEBUZZ) || defined(STM32F3DISCOVERY) +#if defined(STM32F10X) || defined(CHEBUZZ) || defined(STM32F3DISCOVERY) // led strip needs the same ports featureClear(FEATURE_LED_STRIP); #endif @@ -482,7 +491,7 @@ void validateAndFixConfig(void) } -#if defined(STM32F10X_MD) +#if defined(STM32F10X) // led strip needs the same timer as softserial if (feature(FEATURE_SOFTSERIAL)) { featureClear(FEATURE_LED_STRIP); @@ -513,7 +522,7 @@ void validateAndFixConfig(void) void initEEPROM(void) { -#if defined(STM32F10X_MD) +#if defined(STM32F10X) #define FLASH_SIZE_REGISTER 0x1FFFF7E0 @@ -569,10 +578,10 @@ void writeEEPROM(void) // write it FLASH_Unlock(); while (attemptsRemaining--) { -#ifdef STM32F3DISCOVERY +#ifdef STM32F303 FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPERR); #endif -#ifdef STM32F10X_MD +#ifdef 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/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index faa73f44bb..916e925641 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -166,7 +166,7 @@ uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data) #ifdef STM32F303xC SPI_SendData8(instance, data); #endif -#ifdef STM32F10X_MD +#ifdef STM32F10X SPI_I2S_SendData(instance, data); #endif spiTimeout = 1000; @@ -177,7 +177,7 @@ uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data) #ifdef STM32F303xC return ((uint8_t)SPI_ReceiveData8(instance)); #endif -#ifdef STM32F10X_MD +#ifdef STM32F10X return ((uint8_t)SPI_I2S_ReceiveData(instance)); #endif } @@ -194,20 +194,20 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, uint8_t *in, int len) if ((spiTimeout--) == 0) return spiTimeoutUserCallback(instance); } -#ifdef STM32F303xC +#ifdef STM32F303 SPI_I2S_SendData16(instance, b); #endif -#ifdef STM32F10X_MD +#ifdef STM32F10X SPI_I2S_SendData(instance, b); #endif while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) { if ((spiTimeout--) == 0) return spiTimeoutUserCallback(instance); } -#ifdef STM32F303xC +#ifdef STM32F303 b = SPI_I2S_ReceiveData16(instance); #endif -#ifdef STM32F10X_MD +#ifdef STM32F10X b = SPI_I2S_ReceiveData(instance); #endif if (out) diff --git a/src/main/drivers/gpio.h b/src/main/drivers/gpio.h index 96c1371ca2..595140e4c7 100644 --- a/src/main/drivers/gpio.h +++ b/src/main/drivers/gpio.h @@ -17,7 +17,7 @@ #pragma once -#ifdef STM32F10X_MD +#ifdef STM32F10X typedef enum { Mode_AIN = 0x0, diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index ee01adb036..c7987788ee 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -69,7 +69,7 @@ enum { MAP_TO_SERVO_OUTPUT, }; -#if defined(NAZE) || defined(OLIMEXINO) || defined(NAZE32PRO) || defined(STM32F3DISCOVERY) +#if defined(NAZE) || defined(OLIMEXINO) || defined(NAZE32PRO) || defined(STM32F3DISCOVERY) || defined(EUSTM32F103RC) static const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed @@ -277,13 +277,13 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) continue; #endif -#ifdef STM32F10X_MD +#ifdef STM32F10X // skip UART2 ports if (init->useUART2 && (timerIndex == PWM3 || timerIndex == PWM4)) continue; #endif -#ifdef STM32F10X_MD +#ifdef STM32F10X // skip softSerial ports if (init->useSoftSerial && (timerIndex == PWM5 || timerIndex == PWM6 || timerIndex == PWM7 || timerIndex == PWM8)) continue; @@ -302,7 +302,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) continue; #endif -#if defined(STM32F10X_MD) && !defined(CC3D) +#if defined(STM32F10X) && !defined(CC3D) #define LED_STRIP_TIMER TIM3 #endif @@ -310,7 +310,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) #define LED_STRIP_TIMER TIM3 #endif -#if defined(STM32F303xC) +#if defined(STM32F303) #define LED_STRIP_TIMER TIM16 #endif @@ -320,7 +320,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) continue; #endif -#ifdef STM32F10X_MD +#ifdef STM32F10X // skip ADC for RSSI if (init->useRSSIADC && timerIndex == PWM2) continue; @@ -334,7 +334,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) type = 0; if (init->useServos && !init->airplane) { -#if defined(STM32F10X_MD) || defined(CHEBUZZF3) +#if defined(STM32F10X) || defined(CHEBUZZF3) // remap PWM9+10 as servos if (timerIndex == PWM9 || timerIndex == PWM10) type = MAP_TO_SERVO_OUTPUT; diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 4ef366556e..151cccf78c 100755 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -39,7 +39,7 @@ typedef struct drv_pwm_config_t { bool useParallelPWM; bool usePPM; bool useRSSIADC; -#ifdef STM32F10X_MD +#ifdef STM32F10X bool useUART2; #endif bool useSoftSerial; diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index db4f61b3f4..eca09971f1 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -38,7 +38,7 @@ typedef struct { volatile uint32_t *ccr; #endif -#ifdef STM32F10X_MD +#ifdef STM32F10X volatile uint16_t *ccr; #endif uint16_t period; diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index 1b25df1e9e..71f4835536 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -32,14 +32,14 @@ #include "serial.h" #include "serial_softserial.h" -#if defined(STM32F10X_MD) || defined(CHEBUZZF3) +#if defined(STM32F10X) || defined(CHEBUZZF3) #define SOFT_SERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 #define SOFT_SERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6 #define SOFT_SERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7 #define SOFT_SERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 #endif -#if defined(STM32F303xC) && !defined(CHEBUZZF3) +#if defined(STM32F303) && !defined(CHEBUZZF3) #define SOFT_SERIAL_1_TIMER_RX_HARDWARE 8 // PWM 9 #define SOFT_SERIAL_1_TIMER_TX_HARDWARE 9 // PWM 10 #define SOFT_SERIAL_2_TIMER_RX_HARDWARE 10 // PWM 11 diff --git a/src/main/drivers/system.c b/src/main/drivers/system.c index 9a886e5ed6..596ff8c845 100755 --- a/src/main/drivers/system.c +++ b/src/main/drivers/system.c @@ -39,7 +39,7 @@ static volatile uint32_t sysTickUptime = 0; // from system_stm32f30x.c void SetSysClock(void); #endif -#ifdef STM32F10X_MD +#ifdef STM32F10X // from system_stm32f10x.c void SetSysClock(bool overclock); #endif @@ -77,7 +77,7 @@ uint32_t millis(void) void systemInit(bool overclock) { -#ifdef STM32F303xC +#ifdef STM32F303 // start fpu SCB->CPACR = (0x3 << (10*2)) | (0x3 << (11*2)); #endif @@ -85,7 +85,7 @@ void systemInit(bool overclock) #ifdef STM32F303xC SetSysClock(); #endif -#ifdef STM32F10X_MD +#ifdef STM32F10X // Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers // Configure the Flash Latency cycles and enable prefetch buffer SetSysClock(overclock); @@ -94,7 +94,7 @@ void systemInit(bool overclock) // Configure NVIC preempt/priority groups NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2); -#ifdef STM32F10X_MD +#ifdef STM32F10X // Turn on clocks for stuff we use RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE); #endif @@ -105,7 +105,7 @@ void systemInit(bool overclock) enableGPIOPowerUsageAndNoiseReductions(); -#ifdef STM32F10X_MD +#ifdef STM32F10X // Turn off JTAG port 'cause we're using the GPIO for leds #define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24) AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW; diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index 44692fc797..9e55806cbc 100644 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -67,7 +67,7 @@ TIM4 4 channels */ -#if (defined(STM32F10X_MD) || defined(NAZE)) && !defined(CC3D) +#if (defined(STM32F10X) || defined(NAZE)) && !defined(CC3D) const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD}, // PWM1 { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD}, // PWM2 @@ -122,7 +122,7 @@ static const TIM_TypeDef const *timers[MAX_TIMERS] = { #define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB) #endif -#if (defined(STM32F303xC) || defined(STM32F3DISCOVERY)) && !(defined(CHEBUZZF3) || defined(NAZE32PRO)) +#if (defined(STM32F303) || defined(STM32F3DISCOVERY)) && !(defined(CHEBUZZF3) || defined(NAZE32PRO)) const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP_PD}, // PWM1 - PA8 { TIM16, GPIOB, Pin_8, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, Mode_AF_PP_PD}, // PWM2 - PB8 @@ -424,7 +424,7 @@ void TIM4_IRQHandler(void) timCCxHandler(TIM4); } -#if defined(STM32F303xC) || defined(STM32F3DISCOVERY) +#if defined(STM32F303) || defined(STM32F3DISCOVERY) void TIM8_CC_IRQHandler(void) { timCCxHandler(TIM8); @@ -467,7 +467,7 @@ void timerInit(void) #endif -#ifdef STM32F303xC +#ifdef STM32F303 GPIO_PinAFConfig(GPIOA, GPIO_PinSource8, GPIO_AF_6); GPIO_PinAFConfig(GPIOB, GPIO_PinSource8, GPIO_AF_1); GPIO_PinAFConfig(GPIOB, GPIO_PinSource9, GPIO_AF_1); diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index 94331bacac..58bced1342 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -32,7 +32,7 @@ #ifdef STM32F303xC typedef uint32_t captureCompare_t; #endif -#ifdef STM32F10X_MD +#ifdef STM32F10X typedef uint16_t captureCompare_t; #endif diff --git a/src/main/main.c b/src/main/main.c index 3f3abce9a6..33d5b59d6d 100755 --- a/src/main/main.c +++ b/src/main/main.c @@ -185,7 +185,7 @@ void init(void) else pwm_params.airplane = false; -#ifdef STM32F10X_MD +#ifdef STM32F10X if (!feature(FEATURE_RX_PARALLEL_PWM)) { pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2); } diff --git a/src/main/platform.h b/src/main/platform.h index 7327d1f488..d0a6ebf415 100644 --- a/src/main/platform.h +++ b/src/main/platform.h @@ -30,7 +30,7 @@ #endif -#ifdef STM32F10X_MD +#ifdef STM32F10X #include "stm32f10x_conf.h" #include "stm32f10x_gpio.h" @@ -41,7 +41,7 @@ #define U_ID_1 (*(uint32_t*)0x1FFFF7EC) #define U_ID_2 (*(uint32_t*)0x1FFFF7F0) -#endif // STM32F10X_MD +#endif // STM32F10X #include "target.h" diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 5de14deed0..29b5af709f 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -96,7 +96,7 @@ #undef USE_GYRO_SPI_MPU6000 #endif -#if defined(OLIMEXINO) +#if defined(OLIMEXINO) || defined(EUSTM32F103RC) #undef USE_GYRO_L3GD20 #undef USE_GYRO_L3G4200D #undef USE_GYRO_MPU3050 diff --git a/src/main/sensors/sonar.c b/src/main/sensors/sonar.c index e13fc7b788..792db1eeb2 100644 --- a/src/main/sensors/sonar.c +++ b/src/main/sensors/sonar.c @@ -39,7 +39,7 @@ int32_t sonarAlt = -1; // in cm , -1 indicate sonar is not in range void Sonar_init(void) { -#if defined(NAZE) +#if defined(NAZE) || defined(EUSTM32F103RC) static const sonarHardware_t const sonarPWM56 = { .trigger_pin = Pin_8, // PWM5 (PB8) - 5v tolerant .echo_pin = Pin_9, // PWM6 (PB9) - 5v tolerant diff --git a/src/main/startup/startup_stm32f10x_hd_gcc.S b/src/main/startup/startup_stm32f10x_hd_gcc.S new file mode 100644 index 0000000000..4247e15bf1 --- /dev/null +++ b/src/main/startup/startup_stm32f10x_hd_gcc.S @@ -0,0 +1,408 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_hd.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Medium Density Devices vector table for Atollic toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *