diff --git a/Makefile b/Makefile index 5467df99cc..cbec7e609b 100644 --- a/Makefile +++ b/Makefile @@ -14,7 +14,7 @@ # Things that the user might override on the commandline # -# The target to build, must be one of NAZE, FY90Q, OLIMEXINO or STM32F3DISCOVERY +# The target to build, must be one of NAZE, FY90Q, OLIMEXINO, CHEBUZZF3, NAZE32PRO or STM32F3DISCOVERY TARGET ?= NAZE # Compile-time options @@ -32,7 +32,7 @@ SERIAL_DEVICE ?= /dev/ttyUSB0 FORKNAME = cleanflight -VALID_TARGETS = NAZE FY90Q OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 +VALID_TARGETS = NAZE NAZE32PRO FY90Q OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 # Working directories ROOT = $(dir $(lastword $(MAKEFILE_LIST))) @@ -45,7 +45,7 @@ INCLUDE_DIRS = $(SRC_DIR) # Search path for sources VPATH := $(SRC_DIR):$(SRC_DIR)/startup -ifeq ($(TARGET),$(filter $(TARGET),STM32F3DISCOVERY CHEBUZZF3)) +ifeq ($(TARGET),$(filter $(TARGET),STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO)) STDPERIPH_DIR = $(ROOT)/lib/STM32F30x_StdPeriph_Driver @@ -188,9 +188,7 @@ OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \ drivers/timer_common.c \ $(COMMON_SRC) -STM32F3DISCOVERY_COMMON_SRC = startup_stm32f30x_md_gcc.S \ - drivers/accgyro_l3gd20.c \ - drivers/accgyro_lsm303dlhc.c \ +STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S \ drivers/adc_common.c \ drivers/adc_stm32f30x.c \ drivers/bus_i2c_stm32f30x.c \ @@ -204,18 +202,27 @@ STM32F3DISCOVERY_COMMON_SRC = startup_stm32f30x_md_gcc.S \ drivers/serial_softserial.c \ drivers/timer_common.c +NAZE32PRO_SRC = $(STM32F30x_COMMON_SRC) \ + drivers/accgyro_mpu6050.c \ + drivers/compass_hmc5883l.c \ + $(COMMON_SRC) + +STM32F3DISCOVERY_COMMON_SRC = $(STM32F30x_COMMON_SRC) \ + drivers/accgyro_l3gd20.c \ + drivers/accgyro_lsm303dlhc.c + STM32F3DISCOVERY_SRC = $(STM32F3DISCOVERY_COMMON_SRC) \ drivers/accgyro_adxl345.c \ drivers/accgyro_bma280.c \ drivers/accgyro_mma845x.c \ drivers/accgyro_mpu3050.c \ - drivers/accgyro_mpu6050.c \ drivers/accgyro_l3g4200d.c \ $(COMMON_SRC) CHEBUZZF3_SRC = $(STM32F3DISCOVERY_COMMON_SRC) \ $(COMMON_SRC) + # In some cases, %.s regarded as intermediate file, which is actually not. # This will prevent accidental deletion of startup code. .PRECIOUS: %.s diff --git a/src/drivers/serial_softserial.c b/src/drivers/serial_softserial.c index 1197288b43..92c25857eb 100644 --- a/src/drivers/serial_softserial.c +++ b/src/drivers/serial_softserial.c @@ -18,7 +18,7 @@ #define SOFT_SERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 #endif -#if defined(STM32F3DISCOVERY) && !defined(CHEBUZZF3) +#if defined(STM32F303xC) && !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/drivers/system_common.c b/src/drivers/system_common.c index b07b276ec4..bcf80ba668 100755 --- a/src/drivers/system_common.c +++ b/src/drivers/system_common.c @@ -144,7 +144,7 @@ void systemInit(bool overclock) // Make all GPIO in by default to save power and reduce noise gpio.mode = Mode_AIN; gpio.pin = Pin_All; -#ifdef STM32F3DISCOVERY +#ifdef STM32F303xC gpio.pin = Pin_All & ~(Pin_13|Pin_14|Pin_15); // Leave JTAG pins alone gpioInit(GPIOA, &gpio); gpio.pin = Pin_All; @@ -278,6 +278,8 @@ void systemReset(bool toBootloader) if (toBootloader) { // 1FFFF000 -> 20000200 -> SP // 1FFFF004 -> 1FFFF021 -> PC + + // FIXME update for STM32F30x *((uint32_t *)0x20004FF0) = 0xDEADBEEF; // 20KB STM32F103 } diff --git a/src/platform.h b/src/platform.h index 98d4482a7c..9e4551ad65 100644 --- a/src/platform.h +++ b/src/platform.h @@ -1,8 +1,7 @@ #pragma once -#ifdef STM32F3DISCOVERY - +#ifdef STM32F303xC #include "stm32f30x_conf.h" #include "stm32f30x_rcc.h" #include "stm32f30x_gpio.h" @@ -13,6 +12,27 @@ #define U_ID_1 (*(uint32_t*)0x10000000) #define U_ID_2 (*(uint32_t*)0x10000003) +#endif + +#ifdef NAZE32PRO +#define LED0_GPIO GPIOB +#define LED0_PIN Pin_12 +#define BEEP_GPIO GPIOB +#define BEEP_PIN Pin_10 + +#define BUZZER +#define LED0 + +#define GYRO +#define ACC +#define MAG + +#define SENSORS_SET (SENSOR_ACC) + +#endif + +#ifdef STM32F3DISCOVERY + #define LED0_GPIO GPIOE #define LED0_PIN Pin_8|Pin_12 // Blue LEDs - PE8/PE12 #define LED0_INVERTED diff --git a/src/sensors_initialisation.c b/src/sensors_initialisation.c index 7b3fcb80b4..8e334fa0f1 100755 --- a/src/sensors_initialisation.c +++ b/src/sensors_initialisation.c @@ -57,6 +57,17 @@ #undef USE_GYRO_L3GD20 #endif +#ifdef NAZE32PRO +#undef USE_ACC_LSM303DLHC +#undef USE_ACC_ADXL345 +#undef USE_ACC_BMA280 +#undef USE_ACC_MMA8452 +#undef USE_ACC_LSM303DLHC +#undef USE_GYRO_L3G4200D +#undef USE_GYRO_L3GD20 +#undef USE_GYRO_MPU3050 +#endif + #if defined(OLIMEXINO) #undef USE_GYRO_L3GD20 #undef USE_GYRO_L3G4200D