From 7634e4c635db13e6221c659d9f8247162b33a669 Mon Sep 17 00:00:00 2001 From: Michael Jakob Date: Wed, 27 Jan 2016 09:40:58 +0100 Subject: [PATCH] AlienFligth F3 V2 support Updated SPI driver (SPI3 on F3 targets) AK8963 Mag support (part of MPU9250) MPU9250 SPI support via MPU6500 driver Updated LED driver for alternative LED sets Enable gyro intterupt for AlienFlight F3 targets Update AlienWii/AlienFlight documentation Rename AlienWii to AlienFlight --- .travis.yml | 4 +- Makefile | 24 +- build_docs.sh | 2 +- docs/Board - AlienFlight.md | 45 ++++ docs/Board - AlienWii32.md | 38 --- docs/Boards.md | 2 +- docs/Spektrum bind.md | 14 +- fake_travis_build.sh | 4 +- src/main/config/config.c | 15 +- src/main/drivers/accgyro_mpu6500.h | 1 + src/main/drivers/accgyro_spi_mpu6500.c | 7 +- src/main/drivers/bus_spi.c | 163 +++++++++++-- src/main/drivers/compass_ak8963.c | 218 ++++++++++++++++++ src/main/drivers/compass_ak8963.h | 22 ++ src/main/drivers/light_led.h | 37 +-- src/main/drivers/light_led_stm32f10x.c | 59 ++--- src/main/drivers/light_led_stm32f30x.c | 86 ++++--- src/main/drivers/pwm_mapping.c | 2 +- src/main/drivers/timer.c | 2 +- src/main/io/serial_cli.c | 2 +- src/main/io/serial_msp.c | 4 +- src/main/main.c | 23 +- src/main/sensors/compass.h | 5 +- src/main/sensors/initialisation.c | 43 +++- .../target/ALIENFLIGHTF3/hardware_revision.c | 56 +++++ .../target/ALIENFLIGHTF3/hardware_revision.h | 27 +++ .../system_stm32f30x.c | 0 .../system_stm32f30x.h | 0 .../{ALIENWIIF3 => ALIENFLIGHTF3}/target.h | 52 ++++- src/main/target/COLIBRI_RACE/target.h | 4 + src/main/target/IRCFUSIONF3/target.h | 11 - src/main/target/LUX_RACE/target.h | 4 + src/main/target/NAZE/target.h | 6 +- src/main/target/RMDO/target.h | 11 - src/main/target/SPRACINGF3/target.h | 11 - top_makefile | 4 +- 36 files changed, 766 insertions(+), 242 deletions(-) create mode 100644 docs/Board - AlienFlight.md delete mode 100644 docs/Board - AlienWii32.md create mode 100644 src/main/drivers/compass_ak8963.c create mode 100644 src/main/drivers/compass_ak8963.h create mode 100644 src/main/target/ALIENFLIGHTF3/hardware_revision.c create mode 100644 src/main/target/ALIENFLIGHTF3/hardware_revision.h rename src/main/target/{ALIENWIIF3 => ALIENFLIGHTF3}/system_stm32f30x.c (100%) rename src/main/target/{ALIENWIIF3 => ALIENFLIGHTF3}/system_stm32f30x.h (100%) rename src/main/target/{ALIENWIIF3 => ALIENFLIGHTF3}/target.h (73%) diff --git a/.travis.yml b/.travis.yml index b01803eeef5..9efb7f246d6 100644 --- a/.travis.yml +++ b/.travis.yml @@ -19,8 +19,8 @@ env: - TARGET=PORT103R - TARGET=SPARKY - TARGET=STM32F3DISCOVERY - - TARGET=ALIENWIIF1 - - TARGET=ALIENWIIF3 + - TARGET=ALIENFLIGHTF1 + - TARGET=ALIENFLIGHTF3 # use new docker environment sudo: false diff --git a/Makefile b/Makefile index 6ed6ddd2048..2bedb62ce89 100644 --- a/Makefile +++ b/Makefile @@ -42,7 +42,7 @@ FORKNAME = betaflight CC3D_TARGETS = CC3D CC3D_OPBL -VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENWIIF1 ALIENWIIF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI +VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI # Valid targets for OP VCP support VCP_VALID_TARGETS = $(CC3D_TARGETS) @@ -51,10 +51,10 @@ VCP_VALID_TARGETS = $(CC3D_TARGETS) OPBL_VALID_TARGETS = CC3D_OPBL 64K_TARGETS = CJMCU -128K_TARGETS = ALIENWIIF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI -256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENWIIF3 COLIBRI_RACE LUX_RACE MOTOLAB +128K_TARGETS = ALIENFLIGHTF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI +256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB -F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENWIIF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO +F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO # Configure default flash sizes for the targets @@ -221,9 +221,9 @@ endif TARGET_DIR = $(ROOT)/src/main/target/$(TARGET) TARGET_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c)) -ifeq ($(TARGET),ALIENWIIF1) -# ALIENWIIF1 is a VARIANT of NAZE -TARGET_FLAGS := $(TARGET_FLAGS) -DNAZE -DALIENWII32 +ifeq ($(TARGET),ALIENFLIGHTF1) +# ALIENFLIGHTF1 is a VARIANT of NAZE +TARGET_FLAGS := $(TARGET_FLAGS) -DNAZE -DALIENFLIGHT TARGET_DIR = $(ROOT)/src/main/target/NAZE endif @@ -378,7 +378,7 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \ $(HIGHEND_SRC) \ $(COMMON_SRC) -ALIENWIIF1_SRC = $(NAZE_SRC) +ALIENFLIGHTF1_SRC = $(NAZE_SRC) AFROMINI_SRC = $(NAZE_SRC) @@ -612,8 +612,12 @@ SPARKY_SRC = \ $(COMMON_SRC) \ $(VCP_SRC) -ALIENWIIF3_SRC = \ - $(SPARKY_SRC) +ALIENFLIGHTF3_SRC = \ + $(SPARKY_SRC) \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/compass_ak8963.c \ + hardware_revision.c RMDO_SRC = \ $(STM32F30x_COMMON_SRC) \ diff --git a/build_docs.sh b/build_docs.sh index 17fe50c509c..8e8911585cf 100755 --- a/build_docs.sh +++ b/build_docs.sh @@ -28,7 +28,7 @@ doc_files=( 'Blackbox.md' 'Migrating from baseflight.md' 'Boards.md' - 'Board - AlienWii32.md' + 'Board - AlienFlight.md' 'Board - CC3D.md' 'Board - CJMCU.md' 'Board - Naze32.md' diff --git a/docs/Board - AlienFlight.md b/docs/Board - AlienFlight.md new file mode 100644 index 00000000000..f39b5639aaa --- /dev/null +++ b/docs/Board - AlienFlight.md @@ -0,0 +1,45 @@ +# Board - AlienFlight (ALIENFLIGHTF1 and ALIENFLIGHTF3 target) + +AlienWii is now AlienFlight. This target supports various variants of brushed and brusless flight controllers. The designs for them are released for public use at: + +http://www.alienflight.com + +All published designs are flight tested by various people. The intention here is to make this flight controllers available and enable skilled users or RC vendors to build this designs. + +Here are the general hardware specifications for this boards: + +- STM32F103CBT6 MCU (ALIENFLIGHTF1) +- STM32F303CCT6 MCU (ALIENFLIGHTF3) +- MPU6050/6500/9250 accelerometer/gyro(/mag) sensor unit +- The MPU sensor interrupt is connected to the MCU for all new F3 designs and enabled in the firmware +- 4-8 x 4.2A to 9.5A brushed ESCs, integrated, to run the strongest micro motors +- extra-wide traces on the PCB, for maximum power throughput +- USB port, integrated +- (*) serial connection for external DSM2/DSMX sat receiver (e.g. Spektrum SAT, OrangeRx R100, Lemon RX or Deltang Rx31) +- CPPM input +- ground and 3.3V for the receiver +- hardware bind plug for easy binding +- motor connections are at the corners for a clean look with reduced wiring +- small footprint +- direct operation from an single cell lipoly battery +- 3.3V LDO power regulator (older prototypes) +- 3.3V buck-boost power converter (all new versions) +- 5V buck-boost power converter for FPV (some versions) +- battery monitoring with an LED for buzzer functionality (actually for some ALIENFLIGHTF3 variants only) + +(*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator. + + set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit) + set spektrum_sat_bind = 5 + +For more detail of the different bind modes please refer the [Spektrum Bind](Spektrum bind.md) document + +Deltang receivers in serial mode will work like any other Spektrum satellite receiver (10bit, 22ms) only the bind process will be different. + +The pin layout for the ALIENFLIGHTF1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The hardware bind pin is connected to pin 41 (PB5). The pin layout for the ALIENFLIGHTF3 is similar to Sparky. The hardware bind pin is connected to pin 25 (PB12). The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight/AlienWii F3 layouts running the same firmware which takes care on the differences with an hardware detection. + +The AlienFlight firmware will be built as target ALIENFLIGHTF1 or ALIENFLIGHTF3. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with an small Quadcopter. An preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight in an Hexa- or Octocopter or to do some more tuning. Additional configuration changes can be done as usual in the CLI or the Cleanflight configurator. + +## Flashing the firmware + +The firmware can be updated with the Cleanflight configurator as for any other target. All AlienFlight boards have an boot jumper which need to be closed for the initial flashing or for recovery from an broken firmware. \ No newline at end of file diff --git a/docs/Board - AlienWii32.md b/docs/Board - AlienWii32.md deleted file mode 100644 index 8697fe47fea..00000000000 --- a/docs/Board - AlienWii32.md +++ /dev/null @@ -1,38 +0,0 @@ -# Board - AlienWii32 (ALIENWIIF1 and ALIENWIIF3 target) - -The AlienWii32 is actually in prototype stage and few samples exist. There are some different variants and field testing with some users is ongoing. The information below is preliminary and will be updated as needed. - -Here are the hardware specifications: - -- STM32F103CBT6 MCU (ALIENWIIF1) -- STM32F303CCT6 MCU (ALIENWIIF3) -- MPU6050 accelerometer/gyro sensor unit -- 4-8 x 4.2A brushed ESCs, integrated, to run the strongest micro motors -- extra-wide traces on the PCB, for maximum power throughput -- USB port, integrated -- (*) serial connection for external DSM2/DSMX sat receiver (e.g. Spektrum SAT, OrangeRx R100, Lemon RX or Deltang Rx31) -- ground and 3.3V for the receiver -- hardware bind plug for easy binding -- motor connections are at the corners for a clean look with reduced wiring -- dimensions: 29x33mm -- direct operation from an single cell lipoly battery -- 3.3V LDO power regulator (older prototypes) -- 3.3V buck-boost power converter (newer prototypes and production versions) -- battery monitoring with an LED for buzzer functionality (actualy for an ALIENWIIF3 variant) - -(*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator. - - set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit) - set spektrum_sat_bind = 5 - -For more detail of the different bind modes please refer the [Spektrum Bind](Spektrum bind.md) document - -Deltang receivers in serial mode will work like any other Spektrum satellite receiver (10bit, 22ms) only the bind process will be different. - -The pin layout for the ALIENWIIF1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The hardware bind pin is connected to pin 41 (PB5). The pin layout for the ALIENWIIF3 is similar to Sparky. The hardware bind pin is connected to pin 25 (PB12). The AlienWii32 firmware will be built as target ALIENWIIF1 or ALIENWIIF3. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with an small Quadcopter. An preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienWii32. The mixer can be activated with "mixer custom" in the CLI. To use the AlienWii32 in an Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the Cleanflight configurator. - -## Flashing the firmware - -The AlienWii32 F1 board can be flashed like the Naze board or the related clones. All the different methods will work in the same way. - -The AlienWii32 F3 board needs to be flashed via the USB port in DFU mode. Flashing via the Cleanflight GUI is not possible yet. The DFU mode can be activated via setting the BOOT0 jumper during power on of the board. The second method is to connect with an terminal program (i.e. Putty) to the board and enter the character "R" immediately after connecting. Details about the flashing process can be found in the related section of the [Sparky](Board - Sparky.md) documentation. The BOOT0 jumper should be removed and the board needs to be repowerd after firmware flashing. Please be aware, during reboot of the AlienWii F3 board, the GUI will disconnect and an manual reconnect is required. \ No newline at end of file diff --git a/docs/Boards.md b/docs/Boards.md index 4afb25ee9ee..5873c168129 100644 --- a/docs/Boards.md +++ b/docs/Boards.md @@ -4,7 +4,7 @@ The current focus is geared towards flight controller hardware that use the STM3 The core set of supported flyable boards are: -* AlienWii32 +* AlienFlight * CC3D * CJMCU * Flip32+ diff --git a/docs/Spektrum bind.md b/docs/Spektrum bind.md index 6d63d04d337..dc51e506f26 100644 --- a/docs/Spektrum bind.md +++ b/docs/Spektrum bind.md @@ -20,7 +20,7 @@ This is to activate the hardware bind plug feature ## Hardware -The hardware bind plug will be enabled via defining HARDWARE_BIND_PLUG during building of the firmware. BINDPLUG_PORT and BINDPLUG_PIN also need to be defined (please see above). This is done automatically if the AlienWii32 firmware is built. The hardware bind plug is expected between the defined bind pin and ground. +The hardware bind plug will be enabled via defining HARDWARE_BIND_PLUG during building of the firmware. BINDPLUG_PORT and BINDPLUG_PIN also need to be defined (please see above). This is done automatically if the AlienFlight firmware is built. The hardware bind plug is expected between the defined bind pin and ground. ## Function @@ -34,12 +34,12 @@ Please refer to the satellite receiver documentation for more details of the spe ## Table with spektrum_sat_bind parameter value -| Value | Receiver mode | Notes | -| ----- | ------------------| -------------------| -| 3 | DSM2 1024bit/22ms | | -| 5 | DSM2 2048bit/11ms | default AlienWii32 | -| 7 | DSMX 1024bit/22ms | | -| 9 | DSMX 2048bit/11ms | | +| Value | Receiver mode | Notes | +| ----- | ------------------| --------------------| +| 3 | DSM2 1024bit/22ms | | +| 5 | DSM2 2048bit/11ms | default AlienFlight | +| 7 | DSMX 1024bit/22ms | | +| 9 | DSMX 2048bit/11ms | | More detailed information regarding the satellite binding process can be found here: http://wiki.openpilot.org/display/Doc/Spektrum+Satellite diff --git a/fake_travis_build.sh b/fake_travis_build.sh index 88b8beef68e..fdbb6487a44 100644 --- a/fake_travis_build.sh +++ b/fake_travis_build.sh @@ -16,8 +16,8 @@ targets=("PUBLISHMETA=True" \ "TARGET=RMDO" \ "TARGET=SPARKY" \ "TARGET=STM32F3DISCOVERY" \ - "TARGET=ALIENWIIF1" \ - "TARGET=ALIENWIIF3") + "TARGET=ALIENFLIGHTF1" \ + "TARGET=ALIENFLIGHTF3") #fake a travis build environment export TRAVIS_BUILD_NUMBER=$(date +%s) diff --git a/src/main/config/config.c b/src/main/config/config.c index 97e814201c2..c21b0bbed7f 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -606,11 +606,12 @@ static void resetConf(void) featureSet(FEATURE_FAILSAFE); #endif - // alternative defaults settings for ALIENWIIF1 and ALIENWIIF3 targets -#ifdef ALIENWII32 + // alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets +#ifdef ALIENFLIGHT featureSet(FEATURE_RX_SERIAL); featureSet(FEATURE_MOTOR_STOP); -#ifdef ALIENWIIF3 + featureClear(FEATURE_ONESHOT125); +#ifdef ALIENFLIGHTF3 masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL; masterConfig.batteryConfig.vbatscale = 20; #else @@ -621,15 +622,13 @@ static void resetConf(void) masterConfig.escAndServoConfig.minthrottle = 1000; masterConfig.escAndServoConfig.maxthrottle = 2000; masterConfig.motor_pwm_rate = 32000; - currentProfile->pidProfile.pidController = 3; - currentProfile->pidProfile.P8[ROLL] = 36; - currentProfile->pidProfile.P8[PITCH] = 36; + currentProfile->pidProfile.pidController = 2; masterConfig.failsafeConfig.failsafe_delay = 2; masterConfig.failsafeConfig.failsafe_off_delay = 0; - currentControlRateProfile->rcRate8 = 130; + currentControlRateProfile->rcRate8 = 100; currentControlRateProfile->rates[FD_PITCH] = 20; currentControlRateProfile->rates[FD_ROLL] = 20; - currentControlRateProfile->rates[FD_YAW] = 100; + currentControlRateProfile->rates[FD_YAW] = 20; parseRcChannels("TAER1234", &masterConfig.rxConfig); // { 1.0f, -0.414178f, 1.0f, -1.0f }, // REAR_R diff --git a/src/main/drivers/accgyro_mpu6500.h b/src/main/drivers/accgyro_mpu6500.h index f8cc65eb859..92bbef426c8 100644 --- a/src/main/drivers/accgyro_mpu6500.h +++ b/src/main/drivers/accgyro_mpu6500.h @@ -16,6 +16,7 @@ */ #define MPU6500_WHO_AM_I_CONST (0x70) +#define MPU9250_WHO_AM_I_CONST (0x71) #define MPU6500_BIT_RESET (0x80) diff --git a/src/main/drivers/accgyro_spi_mpu6500.c b/src/main/drivers/accgyro_spi_mpu6500.c index 2b2db5e7310..0249c21602c 100755 --- a/src/main/drivers/accgyro_spi_mpu6500.c +++ b/src/main/drivers/accgyro_spi_mpu6500.c @@ -107,10 +107,11 @@ bool mpu6500SpiDetect(void) mpu6500ReadRegister(MPU_RA_WHO_AM_I, 1, &tmp); - if (tmp != MPU6500_WHO_AM_I_CONST) - return false; + if (tmp == MPU6500_WHO_AM_I_CONST || tmp == MPU9250_WHO_AM_I_CONST) { + return true; + } - return true; + return false; } bool mpu6500SpiAccDetect(acc_t *acc) diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index dd46b40a83c..9abcf19c658 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -35,10 +35,12 @@ static volatile uint16_t spi3ErrorCount = 0; #ifdef USE_SPI_DEVICE_1 #ifndef SPI1_GPIO -#define SPI1_GPIO GPIOA -#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOA +#define SPI1_NSS_GPIO GPIOA +#define SPI1_NSS_PERIPHERAL RCC_AHBPeriph_GPIOA #define SPI1_NSS_PIN GPIO_Pin_4 #define SPI1_NSS_PIN_SOURCE GPIO_PinSource4 +#define SPI1_GPIO GPIOA +#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOA #define SPI1_SCK_PIN GPIO_Pin_5 #define SPI1_SCK_PIN_SOURCE GPIO_PinSource5 #define SPI1_MISO_PIN GPIO_Pin_6 @@ -71,7 +73,10 @@ 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 + RCC_AHBPeriphClockCmd(SPI1_NSS_PERIPHERAL, ENABLE); + GPIO_PinAFConfig(SPI1_GPIO, SPI1_NSS_PIN_SOURCE, GPIO_AF_5); #endif // Init pins @@ -89,7 +94,7 @@ void initSpi1(void) GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; - GPIO_Init(SPI1_GPIO, &GPIO_InitStructure); + GPIO_Init(SPI1_NSS_GPIO, &GPIO_InitStructure); #endif #endif @@ -100,20 +105,20 @@ void initSpi1(void) gpio.mode = Mode_AF_PP; gpio.pin = SPI1_MOSI_PIN | SPI1_SCK_PIN; gpio.speed = Speed_50MHz; - gpioInit(GPIOA, &gpio); + gpioInit(SPI1_GPIO, &gpio); // MISO as input gpio.pin = SPI1_MISO_PIN; gpio.mode = Mode_IN_FLOATING; - gpioInit(GPIOA, &gpio); + gpioInit(SPI1_GPIO, &gpio); #ifdef SPI1_NSS_PIN // NSS as gpio slave select gpio.pin = SPI1_NSS_PIN; gpio.mode = Mode_Out_PP; - gpioInit(GPIOA, &gpio); + gpioInit(SPI1_NSS_GPIO, &gpio); #endif #endif - // Init SPI hardware + // Init SPI1 hardware SPI_I2S_DeInit(SPI1); spi.SPI_Mode = SPI_Mode_Master; @@ -133,16 +138,23 @@ void initSpi1(void) SPI_Init(SPI1, &spi); SPI_Cmd(SPI1, ENABLE); + +#ifdef SPI1_NSS_PIN + // Drive NSS high to disable connected SPI device. + GPIO_SetBits(SPI1_NSS_GPIO, SPI1_NSS_PIN); +#endif } #endif #ifdef USE_SPI_DEVICE_2 #ifndef SPI2_GPIO -#define SPI2_GPIO GPIOB -#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB +#define SPI2_NSS_GPIO GPIOB +#define SPI2_NSS_PERIPHERAL RCC_AHBPeriph_GPIOB #define SPI2_NSS_PIN GPIO_Pin_12 #define SPI2_NSS_PIN_SOURCE GPIO_PinSource12 +#define SPI2_GPIO GPIOB +#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB #define SPI2_SCK_PIN GPIO_Pin_13 #define SPI2_SCK_PIN_SOURCE GPIO_PinSource13 #define SPI2_MISO_PIN GPIO_Pin_14 @@ -175,7 +187,10 @@ 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 + RCC_AHBPeriphClockCmd(SPI2_NSS_PERIPHERAL, ENABLE); + GPIO_PinAFConfig(SPI2_GPIO, SPI2_NSS_PIN_SOURCE, GPIO_AF_5); #endif @@ -193,14 +208,13 @@ void initSpi2(void) GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; - GPIO_Init(SPI2_GPIO, &GPIO_InitStructure); + GPIO_Init(SPI2_NSS_GPIO, &GPIO_InitStructure); #endif #endif #ifdef STM32F10X gpio_config_t gpio; - // MOSI + SCK as output gpio.mode = Mode_AF_PP; gpio.pin = SPI2_SCK_PIN | SPI2_MOSI_PIN; @@ -210,45 +224,135 @@ void initSpi2(void) gpio.pin = SPI2_MISO_PIN; 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); + gpioInit(SPI2_NSS_GPIO, &gpio); #endif #endif // Init SPI2 hardware SPI_I2S_DeInit(SPI2); - spi.SPI_Direction = SPI_Direction_2Lines_FullDuplex; spi.SPI_Mode = SPI_Mode_Master; + spi.SPI_Direction = SPI_Direction_2Lines_FullDuplex; spi.SPI_DataSize = SPI_DataSize_8b; - spi.SPI_CPOL = SPI_CPOL_High; - spi.SPI_CPHA = SPI_CPHA_2Edge; spi.SPI_NSS = SPI_NSS_Soft; - spi.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8; spi.SPI_FirstBit = SPI_FirstBit_MSB; spi.SPI_CRCPolynomial = 7; + spi.SPI_CPOL = SPI_CPOL_High; + spi.SPI_CPHA = SPI_CPHA_2Edge; + spi.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8; #ifdef STM32F303xC // Configure for 8-bit reads. SPI_RxFIFOThresholdConfig(SPI2, SPI_RxFIFOThreshold_QF); #endif + SPI_Init(SPI2, &spi); SPI_Cmd(SPI2, ENABLE); +#ifdef SPI2_NSS_PIN // Drive NSS high to disable connected SPI device. - GPIO_SetBits(SPI2_GPIO, SPI2_NSS_PIN); + GPIO_SetBits(SPI2_NSS_GPIO, SPI2_NSS_PIN); +#endif +} +#endif + +#if defined(USE_SPI_DEVICE_3) && defined(STM32F303xC) + +#ifndef SPI3_GPIO +#define SPI3_NSS_GPIO GPIOA +#define SPI3_NSS_PERIPHERAL RCC_AHBPeriph_GPIOA +#define SPI3_NSS_PIN GPIO_Pin_15 +#define SPI3_NSS_PIN_SOURCE GPIO_PinSource15 +#define SPI3_GPIO GPIOB +#define SPI3_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB +#define SPI3_SCK_PIN GPIO_Pin_3 +#define SPI3_SCK_PIN_SOURCE GPIO_PinSource3 +#define SPI3_MISO_PIN GPIO_Pin_4 +#define SPI3_MISO_PIN_SOURCE GPIO_PinSource4 +#define SPI3_MOSI_PIN GPIO_Pin_5 +#define SPI3_MOSI_PIN_SOURCE GPIO_PinSource5 +#endif + +void initSpi3(void) +{ + // Specific to the STM32F303 (AF6) + // SPI3 Driver + // PA15 38 SPI3_NSS + // PB3 39 SPI3_SCK + // PB4 40 SPI3_MISO + // PB5 41 SPI3_MOSI + + SPI_InitTypeDef spi; + + // Enable SPI3 clock + RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI3, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE); + + GPIO_InitTypeDef GPIO_InitStructure; + + RCC_AHBPeriphClockCmd(SPI3_GPIO_PERIPHERAL, ENABLE); + + GPIO_PinAFConfig(SPI3_GPIO, SPI3_SCK_PIN_SOURCE, GPIO_AF_6); + GPIO_PinAFConfig(SPI3_GPIO, SPI3_MISO_PIN_SOURCE, GPIO_AF_6); + GPIO_PinAFConfig(SPI3_GPIO, SPI3_MOSI_PIN_SOURCE, GPIO_AF_6); +#ifdef SPI2_NSS_PIN_SOURCE + RCC_AHBPeriphClockCmd(SPI3_NSS_PERIPHERAL, ENABLE); + + GPIO_PinAFConfig(SPI3_NSS_GPIO, SPI3_NSS_PIN_SOURCE, GPIO_AF_6); +#endif + + // Init pins + GPIO_InitStructure.GPIO_Pin = SPI3_SCK_PIN | SPI3_MISO_PIN | SPI3_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(SPI3_GPIO, &GPIO_InitStructure); + +#ifdef SPI3_NSS_PIN + GPIO_InitStructure.GPIO_Pin = SPI3_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(SPI3_NSS_GPIO, &GPIO_InitStructure); +#endif + + // Init SPI hardware + SPI_I2S_DeInit(SPI3); + + spi.SPI_Mode = SPI_Mode_Master; + spi.SPI_Direction = SPI_Direction_2Lines_FullDuplex; + spi.SPI_DataSize = SPI_DataSize_8b; + spi.SPI_NSS = SPI_NSS_Soft; + spi.SPI_FirstBit = SPI_FirstBit_MSB; + spi.SPI_CRCPolynomial = 7; + spi.SPI_CPOL = SPI_CPOL_High; + spi.SPI_CPHA = SPI_CPHA_2Edge; + spi.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8; + + // Configure for 8-bit reads. + SPI_RxFIFOThresholdConfig(SPI3, SPI_RxFIFOThreshold_QF); + + SPI_Init(SPI3, &spi); + SPI_Cmd(SPI3, ENABLE); +#ifdef SPI3_NSS_PIN + // Drive NSS high to disable connected SPI device. + GPIO_SetBits(SPI3_NSS_GPIO, SPI3_NSS_PIN); +#endif } #endif bool spiInit(SPI_TypeDef *instance) { -#if (!(defined(USE_SPI_DEVICE_1) && defined(USE_SPI_DEVICE_2))) +#if (!(defined(USE_SPI_DEVICE_1) && defined(USE_SPI_DEVICE_2) && defined(USE_SPI_DEVICE_3))) UNUSED(instance); #endif @@ -263,6 +367,12 @@ bool spiInit(SPI_TypeDef *instance) initSpi2(); return true; } +#endif +#if defined(USE_SPI_DEVICE_3) && defined(STM32F303xC) + if (instance == SPI3) { + initSpi3(); + return true; + } #endif return false; } @@ -271,15 +381,16 @@ uint32_t spiTimeoutUserCallback(SPI_TypeDef *instance) { if (instance == SPI1) { spi1ErrorCount++; + return spi1ErrorCount; } else if (instance == SPI2) { spi2ErrorCount++; - } + return spi2ErrorCount; #ifdef STM32F303xC - else { + } else if (instance == SPI3) { spi3ErrorCount++; return spi3ErrorCount; - } #endif + } return -1; } @@ -412,6 +523,10 @@ uint16_t spiGetErrorCounter(SPI_TypeDef *instance) return spi1ErrorCount; } else if (instance == SPI2) { return spi2ErrorCount; +#ifdef STM32F303xC + } else if (instance == SPI3) { + return spi3ErrorCount; +#endif } return 0; } @@ -422,6 +537,10 @@ void spiResetErrorCounter(SPI_TypeDef *instance) spi1ErrorCount = 0; } else if (instance == SPI2) { spi2ErrorCount = 0; +#ifdef STM32F303xC + } else if (instance == SPI3) { + spi3ErrorCount = 0; +#endif } } diff --git a/src/main/drivers/compass_ak8963.c b/src/main/drivers/compass_ak8963.c new file mode 100644 index 00000000000..fc583a18dbe --- /dev/null +++ b/src/main/drivers/compass_ak8963.c @@ -0,0 +1,218 @@ +/* + * 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 . + */ + +#include +#include + +#include + +#include "build_config.h" + +#include "platform.h" + +#include "common/axis.h" +#include "common/maths.h" + +#include "system.h" +#include "gpio.h" +#include "exti.h" +#include "bus_i2c.h" + +#include "sensors/boardalignment.h" +#include "sensors/sensors.h" + +#include "sensor.h" +#include "compass.h" + +#include "accgyro.h" +#include "accgyro_mpu.h" +#include "accgyro_spi_mpu6500.h" +#include "compass_ak8963.h" + +// This sensor is available in MPU-9250. + +// AK8963, mag sensor address +#define AK8963_MAG_I2C_ADDRESS 0x0C +#define AK8963_Device_ID 0x48 + +// Registers +#define AK8963_MAG_REG_WHO_AM_I 0x00 +#define AK8963_MAG_REG_INFO 0x01 +#define AK8963_MAG_REG_STATUS1 0x02 +#define AK8963_MAG_REG_HXL 0x03 +#define AK8963_MAG_REG_HXH 0x04 +#define AK8963_MAG_REG_HYL 0x05 +#define AK8963_MAG_REG_HYH 0x06 +#define AK8963_MAG_REG_HZL 0x07 +#define AK8963_MAG_REG_HZH 0x08 +#define AK8963_MAG_REG_STATUS2 0x09 +#define AK8963_MAG_REG_CNTL 0x0a +#define AK8963_MAG_REG_ASCT 0x0c // self test +#define AK8963_MAG_REG_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value +#define AK8963_MAG_REG_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value +#define AK8963_MAG_REG_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value + +#define READ_FLAG 0x80 + +#define STATUS1_DATA_READY 0x01 + +#define STATUS2_DATA_ERROR 0x02 +#define STATUS2_MAG_SENSOR_OVERFLOW 0x03 + +#define CNTL_MODE_POWER_DOWN 0x00 +#define CNTL_MODE_ONCE 0x01 +#define CNTL_MODE_CONT1 0x02 +#define CNTL_MODE_CONT2 0x06 +#define CNTL_MODE_SELF_TEST 0x08 +#define CNTL_MODE_FUSE_ROM 0x0F + +typedef bool (*ak8963ReadRegisterFunc)(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf); +typedef bool (*ak8963WriteRegisterFunc)(uint8_t addr_, uint8_t reg_, uint8_t data); + +typedef struct ak8963Configuration_s { + ak8963ReadRegisterFunc read; + ak8963WriteRegisterFunc write; +} ak8963Configuration_t; + +ak8963Configuration_t ak8963config; +static float magGain[3] = { 1.0f, 1.0f, 1.0f }; + +#ifdef USE_SPI +bool ak8963SPIRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf) +{ + mpu6500WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read + mpu6500WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register + mpu6500WriteRegister(MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes + delay(8); + __disable_irq(); + mpu6500ReadRegister(MPU_RA_EXT_SENS_DATA_00, len_, buf); // read I2C + __enable_irq(); + return true; +} + +bool ak8963SPIWrite(uint8_t addr_, uint8_t reg_, uint8_t data) +{ + mpu6500WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_); // set I2C slave address for write + mpu6500WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register + mpu6500WriteRegister(MPU_RA_I2C_SLV0_DO, data); // set I2C salve value + mpu6500WriteRegister(MPU_RA_I2C_SLV0_CTRL, 0x81); // write 1 byte + return true; +} +#endif + +bool ak8963Detect(mag_t *mag) +{ + bool ack = false; + uint8_t sig = 0; + +#ifdef USE_I2C + // check for AK8963 on I2C bus + ack = i2cRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig); + if (ack && sig == AK8963_Device_ID) // 0x48 / 01001000 / 'H' + { + ak8963config.read = i2cRead; + ak8963config.write = i2cWrite; + mag->init = ak8963Init; + mag->read = ak8963Read; + + return true; + } +#endif + +#ifdef USE_SPI + // check for AK8963 on I2C master via SPI bus (as part of MPU9250) + + ack = mpu6500WriteRegister(MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR + delay(10); + + ack = mpu6500WriteRegister(MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz + delay(10); + + ack = mpu6500WriteRegister(MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only + delay(10); + + ack = ak8963SPIRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig); + if (ack && sig == AK8963_Device_ID) // 0x48 / 01001000 / 'H' + { + ak8963config.read = ak8963SPIRead; + ak8963config.write = ak8963SPIWrite; + mag->init = ak8963Init; + mag->read = ak8963Read; + + return true; + } +#endif + return false; +} + +void ak8963Init() +{ + bool ack; + UNUSED(ack); + uint8_t calibration[3]; + uint8_t status; + + ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down before entering fuse mode + delay(20); + + ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_FUSE_ROM); // Enter Fuse ROM access mode + delay(10); + + ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_ASAX, sizeof(calibration), calibration); // Read the x-, y-, and z-axis calibration values + delay(10); + + magGain[X] = (((((float)(int8_t)calibration[X] - 128) / 256) + 1) * 30); + magGain[Y] = (((((float)(int8_t)calibration[Y] - 128) / 256) + 1) * 30); + magGain[Z] = (((((float)(int8_t)calibration[Z] - 128) / 256) + 1) * 30); + + ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down after reading. + delay(10); + + // Clear status registers + ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &status); + ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status); + + // Trigger first measurement + ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE); +} + +bool ak8963Read(int16_t *magData) +{ + bool ack; + uint8_t status; + uint8_t buf[6]; + + ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &status); + + if (!ack || (status & STATUS1_DATA_READY) == 0) { + return false; + } + + ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, sizeof(buf), buf); + + ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status); + + if (!ack || (status & STATUS2_DATA_ERROR) || (status & STATUS2_MAG_SENSOR_OVERFLOW)) { + return false; + } + + magData[X] = -(int16_t)(buf[1] << 8 | buf[0]) * magGain[X]; + magData[Y] = -(int16_t)(buf[3] << 8 | buf[2]) * magGain[Y]; + magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * magGain[Z]; + + return ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE); // start reading again +} diff --git a/src/main/drivers/compass_ak8963.h b/src/main/drivers/compass_ak8963.h new file mode 100644 index 00000000000..9806a1d1c85 --- /dev/null +++ b/src/main/drivers/compass_ak8963.h @@ -0,0 +1,22 @@ +/* + * 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 . + */ + +#pragma once + +bool ak8963Detect(mag_t *mag); +void ak8963Init(void); +bool ak8963Read(int16_t *magData); diff --git a/src/main/drivers/light_led.h b/src/main/drivers/light_led.h index cf6a2bea97f..83d436d6f77 100644 --- a/src/main/drivers/light_led.h +++ b/src/main/drivers/light_led.h @@ -17,15 +17,20 @@ #pragma once +struct { + GPIO_TypeDef *gpio; + uint16_t pin; +} led_config[3]; + // Helpful macros #ifdef LED0 -#define LED0_TOGGLE digitalToggle(LED0_GPIO, LED0_PIN) +#define LED0_TOGGLE digitalToggle(led_config[0].gpio, led_config[0].pin) #ifndef LED0_INVERTED -#define LED0_OFF digitalHi(LED0_GPIO, LED0_PIN) -#define LED0_ON digitalLo(LED0_GPIO, LED0_PIN) +#define LED0_OFF digitalHi(led_config[0].gpio, led_config[0].pin) +#define LED0_ON digitalLo(led_config[0].gpio, led_config[0].pin) #else -#define LED0_OFF digitalLo(LED0_GPIO, LED0_PIN) -#define LED0_ON digitalHi(LED0_GPIO, LED0_PIN) +#define LED0_OFF digitalLo(led_config[0].gpio, led_config[0].pin) +#define LED0_ON digitalHi(led_config[0].gpio, led_config[0].pin) #endif // inverted #else #define LED0_TOGGLE do {} while(0) @@ -34,13 +39,13 @@ #endif #ifdef LED1 -#define LED1_TOGGLE digitalToggle(LED1_GPIO, LED1_PIN) +#define LED1_TOGGLE digitalToggle(led_config[1].gpio, led_config[1].pin) #ifndef LED1_INVERTED -#define LED1_OFF digitalHi(LED1_GPIO, LED1_PIN) -#define LED1_ON digitalLo(LED1_GPIO, LED1_PIN) +#define LED1_OFF digitalHi(led_config[1].gpio, led_config[1].pin) +#define LED1_ON digitalLo(led_config[1].gpio, led_config[1].pin) #else -#define LED1_OFF digitalLo(LED1_GPIO, LED1_PIN) -#define LED1_ON digitalHi(LED1_GPIO, LED1_PIN) +#define LED1_OFF digitalLo(led_config[1].gpio, led_config[1].pin) +#define LED1_ON digitalHi(led_config[1].gpio, led_config[1].pin) #endif // inverted #else #define LED1_TOGGLE do {} while(0) @@ -50,13 +55,13 @@ #ifdef LED2 -#define LED2_TOGGLE digitalToggle(LED2_GPIO, LED2_PIN) +#define LED2_TOGGLE digitalToggle(led_config[2].gpio, led_config[2].pin) #ifndef LED2_INVERTED -#define LED2_OFF digitalHi(LED2_GPIO, LED2_PIN) -#define LED2_ON digitalLo(LED2_GPIO, LED2_PIN) +#define LED2_OFF digitalHi(led_config[2].gpio, led_config[2].pin) +#define LED2_ON digitalLo(led_config[2].gpio, led_config[2].pin) #else -#define LED2_OFF digitalLo(LED2_GPIO, LED2_PIN) -#define LED2_ON digitalHi(LED2_GPIO, LED2_PIN) +#define LED2_OFF digitalLo(led_config[2].gpio, led_config[2].pin) +#define LED2_ON digitalHi(led_config[2].gpio, led_config[2].pin) #endif // inverted #else #define LED2_TOGGLE do {} while(0) @@ -64,4 +69,4 @@ #define LED2_ON do {} while(0) #endif -void ledInit(void); +void ledInit(bool alternative_led); diff --git a/src/main/drivers/light_led_stm32f10x.c b/src/main/drivers/light_led_stm32f10x.c index 383818e3f51..ff9dd9b31c9 100644 --- a/src/main/drivers/light_led_stm32f10x.c +++ b/src/main/drivers/light_led_stm32f10x.c @@ -28,56 +28,37 @@ #include "light_led.h" - -void ledInit(void) +void ledInit(bool alternative_led) { + UNUSED(alternative_led); #if defined(LED0) || defined(LED1) || defined(LED2) - uint32_t i; - - struct { - GPIO_TypeDef *gpio; - gpio_config_t cfg; - } gpio_setup[] = { -#ifdef LED0 - { - .gpio = LED0_GPIO, - .cfg = { LED0_PIN, Mode_Out_PP, Speed_2MHz } - }, -#endif -#ifdef LED1 - { - .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 - }; - - uint8_t gpio_count = ARRAYLEN(gpio_setup); - + gpio_config_t cfg; + cfg.mode = Mode_Out_PP; + cfg.speed = Speed_2MHz; #ifdef LED0 RCC_APB2PeriphClockCmd(LED0_PERIPHERAL, ENABLE); + led_config[0].gpio = LED0_GPIO; + led_config[0].pin = LED0_PIN; + cfg.pin = led_config[0].pin; + LED0_OFF; + gpioInit(led_config[0].gpio, &cfg); #endif #ifdef LED1 RCC_APB2PeriphClockCmd(LED1_PERIPHERAL, ENABLE); + led_config[1].gpio = LED1_GPIO; + led_config[1].pin = LED1_PIN; + cfg.pin = led_config[1].pin; + LED1_OFF; + gpioInit(led_config[1].gpio, &cfg); #endif #ifdef LED2 RCC_APB2PeriphClockCmd(LED2_PERIPHERAL, ENABLE); -#endif - - LED0_OFF; - LED1_OFF; + led_config[2].gpio = LED2_GPIO; + led_config[2].pin = LED2_PIN; + cfg.pin = led_config[2].pin; LED2_OFF; - - for (i = 0; i < gpio_count; i++) { - gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg); - } - + gpioInit(led_config[2].gpio, &cfg); +#endif #endif } diff --git a/src/main/drivers/light_led_stm32f30x.c b/src/main/drivers/light_led_stm32f30x.c index cce6a0650be..e2e2af1e98f 100644 --- a/src/main/drivers/light_led_stm32f30x.c +++ b/src/main/drivers/light_led_stm32f30x.c @@ -27,52 +27,62 @@ #include "light_led.h" -void ledInit(void) +void ledInit(bool alternative_led) { - uint32_t i; - - struct { - GPIO_TypeDef *gpio; - gpio_config_t cfg; - } gpio_setup[] = { +#if defined(LED0) || defined(LED1) || defined(LED2) + gpio_config_t cfg; + cfg.mode = Mode_Out_PP; + cfg.speed = Speed_2MHz; #ifdef LED0 - { - .gpio = LED0_GPIO, - .cfg = { LED0_PIN, Mode_Out_PP, Speed_2MHz } - }, -#endif -#ifdef LED1 - { - .gpio = LED1_GPIO, - .cfg = { LED1_PIN, Mode_Out_PP, Speed_2MHz } - }, + if (alternative_led) { +#ifdef LED0_PERIPHERAL_2 + RCC_AHBPeriphClockCmd(LED0_PERIPHERAL_2, ENABLE); + led_config[0].gpio = LED0_GPIO_2; + led_config[0].pin = LED0_PIN_2; #endif -#ifdef LED2 - { - .gpio = LED2_GPIO, - .cfg = { LED2_PIN, Mode_Out_PP, Speed_2MHz } - } -#endif - }; - - uint8_t gpio_count = ARRAYLEN(gpio_setup); - -#ifdef LED0 - RCC_AHBPeriphClockCmd(LED0_PERIPHERAL, ENABLE); + } else { + RCC_AHBPeriphClockCmd(LED0_PERIPHERAL, ENABLE); + led_config[0].gpio = LED0_GPIO; + led_config[0].pin = LED0_PIN; + } + cfg.pin = led_config[0].pin; + LED0_OFF; + gpioInit(led_config[0].gpio, &cfg); #endif #ifdef LED1 - RCC_AHBPeriphClockCmd(LED1_PERIPHERAL, ENABLE); + if (alternative_led) { +#ifdef LED1_PERIPHERAL_2 + RCC_AHBPeriphClockCmd(LED1_PERIPHERAL_2, ENABLE); + led_config[1].gpio = LED1_GPIO_2; + led_config[1].pin = LED1_PIN_2; +#endif + } else { + RCC_AHBPeriphClockCmd(LED1_PERIPHERAL, ENABLE); + led_config[1].gpio = LED1_GPIO; + led_config[1].pin = LED1_PIN; + } + cfg.pin = led_config[1].pin; + LED1_OFF; + gpioInit(led_config[1].gpio, &cfg); #endif #ifdef LED2 - RCC_AHBPeriphClockCmd(LED2_PERIPHERAL, ENABLE); + if (alternative_led) { +#ifdef LED2_PERIPHERAL_2 + RCC_AHBPeriphClockCmd(LED2_PERIPHERAL_2, ENABLE); + led_config[2].gpio = LED2_GPIO_2; + led_config[2].pin = LED2_PIN_2; #endif - - LED0_OFF; - LED1_OFF; - LED2_OFF; - - for (i = 0; i < gpio_count; i++) { - gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg); + } else { + RCC_AHBPeriphClockCmd(LED2_PERIPHERAL, ENABLE); + led_config[2].gpio = LED2_GPIO; + led_config[2].pin = LED2_PIN; } + cfg.pin = led_config[2].pin; + LED2_OFF; + gpioInit(led_config[2].gpio, &cfg); +#endif +#else + UNUSED(alternative_led); +#endif } diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index ca97f9c9cae..598b6c65f06 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -364,7 +364,7 @@ static const uint16_t airPWM[] = { }; #endif -#if defined(SPARKY) || defined(ALIENWIIF3) +#if defined(SPARKY) || defined(ALIENFLIGHTF3) static const uint16_t multiPPM[] = { PWM11 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index f7778c9f622..76fb8e8f869 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -201,7 +201,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { #endif -#if defined(SPARKY) || defined(ALIENWIIF3) +#if defined(SPARKY) || defined(ALIENFLIGHTF3) const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // // 6 x 3 pin headers diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 6bb2bac0805..d89d60d233f 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -197,7 +197,7 @@ static const char * const sensorHardwareNames[4][11] = { { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "FAKE", NULL }, { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", NULL }, { "", "None", "BMP085", "MS5611", "BMP280", NULL }, - { "", "None", "HMC5883", "AK8975", NULL } + { "", "None", "HMC5883", "AK8975", "AK8963", NULL } }; #endif diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index d10399a1d41..98c1b1671d3 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -81,7 +81,7 @@ #include "config/config_master.h" #include "version.h" -#ifdef NAZE +#ifdef USE_HARDWARE_REVISION_DETECTION #include "hardware_revision.h" #endif @@ -766,7 +766,7 @@ static bool processOutCommand(uint8_t cmdMSP) for (i = 0; i < BOARD_IDENTIFIER_LENGTH; i++) { serialize8(boardIdentifier[i]); } -#ifdef NAZE +#ifdef USE_HARDWARE_REVISION_DETECTION serialize16(hardwareRevision); #else serialize16(0); // No other build targets currently have hardware revision detection. diff --git a/src/main/main.c b/src/main/main.c index 8402c3e9381..8e4cc1f6a9d 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -173,16 +173,24 @@ void init(void) #endif //i2cSetOverclock(masterConfig.i2c_overclock); + systemInit(); + #ifdef USE_HARDWARE_REVISION_DETECTION detectHardwareRevision(); #endif - systemInit(); - // Latch active features to be used for feature() in the remainder of init(). latchActiveFeatures(); - ledInit(); +#ifdef ALIENFLIGHTF3 + if (hardwareRevision == AFF3_REV_1) { + ledInit(false); + } else { + ledInit(true); + } +#else + ledInit(false); +#endif #ifdef SPEKTRUM_BIND if (feature(FEATURE_RX_SERIAL)) { @@ -324,6 +332,15 @@ void init(void) #ifdef USE_SPI spiInit(SPI1); spiInit(SPI2); +#ifdef STM32F303xC +#ifdef ALIENFLIGHTF3 + if (hardwareRevision == AFF3_REV_2) { + spiInit(SPI3); + } +#else + spiInit(SPI3); +#endif +#endif #endif #ifdef USE_HARDWARE_REVISION_DETECTION diff --git a/src/main/sensors/compass.h b/src/main/sensors/compass.h index 8c1eb719947..45af108d4a2 100644 --- a/src/main/sensors/compass.h +++ b/src/main/sensors/compass.h @@ -22,10 +22,11 @@ typedef enum { MAG_DEFAULT = 0, MAG_NONE = 1, MAG_HMC5883 = 2, - MAG_AK8975 = 3 + MAG_AK8975 = 3, + MAG_AK8963 = 4 } magSensor_e; -#define MAG_MAX MAG_AK8975 +#define MAG_MAX MAG_AK8963 #ifdef MAG void compassInit(void); diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index e147acf6e3a..0cdcd04852e 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -55,6 +55,7 @@ #include "drivers/compass.h" #include "drivers/compass_hmc5883l.h" #include "drivers/compass_ak8975.h" +#include "drivers/compass_ak8963.h" #include "drivers/sonar_hcsr04.h" @@ -68,7 +69,7 @@ #include "sensors/sonar.h" #include "sensors/initialisation.h" -#ifdef NAZE +#ifdef USE_HARDWARE_REVISION_DETECTION #include "hardware_revision.h" #endif @@ -168,6 +169,34 @@ const extiConfig_t *selectMPUIntExtiConfig(void) return &MotolabF3MPU6050Config; #endif +#ifdef ALIENFLIGHTF3 + // MPU_INT output on V1 PA15 + static const extiConfig_t alienWiiF3V1MPUIntExtiConfig = { + .gpioAHBPeripherals = RCC_AHBPeriph_GPIOA, + .gpioPort = GPIOA, + .gpioPin = Pin_15, + .exti_port_source = EXTI_PortSourceGPIOA, + .exti_pin_source = EXTI_PinSource15, + .exti_line = EXTI_Line15, + .exti_irqn = EXTI15_10_IRQn + }; + // MPU_INT output on V2 PB13 + static const extiConfig_t alienWiiF3V2MPUIntExtiConfig = { + .gpioAHBPeripherals = RCC_AHBPeriph_GPIOB, + .gpioPort = GPIOB, + .gpioPin = Pin_13, + .exti_port_source = EXTI_PortSourceGPIOB, + .exti_pin_source = EXTI_PinSource13, + .exti_line = EXTI_Line13, + .exti_irqn = EXTI15_10_IRQn + }; + if (hardwareRevision == AFF3_REV_1) { + return &alienWiiF3V1MPUIntExtiConfig; + } else { + return &alienWiiF3V2MPUIntExtiConfig; + } +#endif + return NULL; } @@ -616,6 +645,18 @@ static void detectMag(magSensor_e magHardwareToUse) #endif ; // fallthrough + case MAG_AK8963: +#ifdef USE_MAG_AK8963 + if (ak8963Detect(&mag)) { +#ifdef MAG_AK8963_ALIGN + magAlign = MAG_AK8963_ALIGN; +#endif + magHardware = MAG_AK8963; + break; + } +#endif + ; // fallthrough + case MAG_NONE: magHardware = MAG_NONE; break; diff --git a/src/main/target/ALIENFLIGHTF3/hardware_revision.c b/src/main/target/ALIENFLIGHTF3/hardware_revision.c new file mode 100644 index 00000000000..8ccb6914331 --- /dev/null +++ b/src/main/target/ALIENFLIGHTF3/hardware_revision.c @@ -0,0 +1,56 @@ +/* + * 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 . + */ + +#include +#include +#include + +#include "platform.h" + +#include "build_config.h" + +#include "drivers/system.h" +#include "drivers/gpio.h" + +#include "hardware_revision.h" + +static const char * const hardwareRevisionNames[] = { + "Unknown", + "AlienFlight V1", + "AlienFlight V2" +}; + +uint8_t hardwareRevision = UNKNOWN; + +void detectHardwareRevision(void) +{ + gpio_config_t cfg = {HW_PIN, Mode_IPU, Speed_2MHz}; + RCC_AHBPeriphClockCmd(HW_PERIPHERAL, ENABLE); + gpioInit(HW_GPIO, &cfg); + + // Check hardware revision + delayMicroseconds(10); // allow configuration to settle + if (digitalIn(HW_GPIO, HW_PIN)) { + hardwareRevision = AFF3_REV_1; + } else { + hardwareRevision = AFF3_REV_2; + } +} + +void updateHardwareRevision(void) +{ +} diff --git a/src/main/target/ALIENFLIGHTF3/hardware_revision.h b/src/main/target/ALIENFLIGHTF3/hardware_revision.h new file mode 100644 index 00000000000..f4c0e909528 --- /dev/null +++ b/src/main/target/ALIENFLIGHTF3/hardware_revision.h @@ -0,0 +1,27 @@ +/* + * 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 . + */ + +typedef enum awf3HardwareRevision_t { + UNKNOWN = 0, + AFF3_REV_1, // MPU6050 / MPU9150 (I2C) + AFF3_REV_2 // MPU6500 / MPU9250 (SPI) +} awf3HardwareRevision_e; + +extern uint8_t hardwareRevision; + +void updateHardwareRevision(void); +void detectHardwareRevision(void); diff --git a/src/main/target/ALIENWIIF3/system_stm32f30x.c b/src/main/target/ALIENFLIGHTF3/system_stm32f30x.c similarity index 100% rename from src/main/target/ALIENWIIF3/system_stm32f30x.c rename to src/main/target/ALIENFLIGHTF3/system_stm32f30x.c diff --git a/src/main/target/ALIENWIIF3/system_stm32f30x.h b/src/main/target/ALIENFLIGHTF3/system_stm32f30x.h similarity index 100% rename from src/main/target/ALIENWIIF3/system_stm32f30x.h rename to src/main/target/ALIENFLIGHTF3/system_stm32f30x.h diff --git a/src/main/target/ALIENWIIF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h similarity index 73% rename from src/main/target/ALIENWIIF3/target.h rename to src/main/target/ALIENFLIGHTF3/target.h index ff3716f1db1..69f4fab01c8 100644 --- a/src/main/target/ALIENWIIF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -17,40 +17,66 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "AWF3" // AlienWii32 F3. +#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3. +#define USE_HARDWARE_REVISION_DETECTION +#define HW_GPIO GPIOB +#define HW_PIN Pin_2 +#define HW_PERIPHERAL RCC_AHBPeriph_GPIOB + +// LED's V1 #define LED0_GPIO GPIOB #define LED0_PIN Pin_4 // Blue LEDs - PB4 #define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB #define LED1_GPIO GPIOB #define LED1_PIN Pin_5 // Green LEDs - PB5 #define LED1_PERIPHERAL RCC_AHBPeriph_GPIOB + +// LED's V2 +#define LED0_GPIO_2 GPIOB +#define LED0_PIN_2 Pin_8 // Blue LEDs - PB8 +#define LED0_PERIPHERAL_2 RCC_AHBPeriph_GPIOB +#define LED1_GPIO_2 GPIOB +#define LED1_PIN_2 Pin_9 // Green LEDs - PB9 +#define LED1_PERIPHERAL_2 RCC_AHBPeriph_GPIOB + #define BEEP_GPIO GPIOA #define BEEP_PIN Pin_5 // White LEDs - PA5 #define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOA #define USABLE_TIMER_CHANNEL_COUNT 11 +#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready + +#define DEBUG_MPU_DATA_READY_INTERRUPT +#define USE_MPU_DATA_READY_SIGNAL + // Using MPU6050 for the moment. #define GYRO #define USE_GYRO_MPU6050 +#define USE_GYRO_MPU6500 +#define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6050_ALIGN CW270_DEG +#define GYRO_MPU6500_ALIGN CW270_DEG #define ACC #define USE_ACC_MPU6050 +#define USE_ACC_MPU6500 +#define USE_ACC_SPI_MPU6500 #define ACC_MPU6050_ALIGN CW270_DEG +#define ACC_MPU6500_ALIGN CW270_DEG // No baro support. //#define BARO //#define USE_BARO_MS5611 // No mag support for now (option to use MPU9150 in the future). -//#define MAG -//#define USE_MAG_AK8975 +#define MAG +#define USE_MAG_AK8963 -#define MAG_AK8975_ALIGN CW0_DEG_FLIP +#define MAG_AK8963_ALIGN CW0_DEG_FLIP #define BEEPER #define LED0 @@ -98,6 +124,20 @@ #define I2C2_SDA_PIN_SOURCE GPIO_PinSource10 #define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA +// SPI3 +// PA15 38 SPI3_NSS +// PB3 39 SPI3_SCK +// PB4 40 SPI3_MISO +// PB5 41 SPI3_MOSI + +#define USE_SPI +#define USE_SPI_DEVICE_3 + +#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA +#define MPU6500_CS_GPIO GPIOA +#define MPU6500_CS_PIN GPIO_Pin_15 +#define MPU6500_SPI_INSTANCE SPI3 + #define USE_ADC #define ADC_INSTANCE ADC2 @@ -123,8 +163,8 @@ #define BIND_PORT GPIOA #define BIND_PIN Pin_3 -// alternative defaults for AlienWii32 F3 target -#define ALIENWII32 +// alternative defaults for AlienFlight F3 target +#define ALIENFLIGHT #define HARDWARE_BIND_PLUG // Hardware bind plug at PB12 (Pin 25) diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index b9520a7f334..ea6a936f5b4 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -46,6 +46,10 @@ #define USE_SPI #define USE_SPI_DEVICE_1 +#define SPI1_NSS_GPIO GPIOA +#define SPI1_NSS_PERIPHERAL RCC_AHBPeriph_GPIOA +#define SPI1_NSS_PIN GPIO_Pin_4 +#define SPI1_NSS_PIN_SOURCE GPIO_PinSource4 #define SPI1_GPIO GPIOB #define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB #define SPI1_SCK_PIN GPIO_Pin_3 diff --git a/src/main/target/IRCFUSIONF3/target.h b/src/main/target/IRCFUSIONF3/target.h index bdc81122f90..4ce2ab86f48 100644 --- a/src/main/target/IRCFUSIONF3/target.h +++ b/src/main/target/IRCFUSIONF3/target.h @@ -108,17 +108,6 @@ #define USE_SPI #define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 -#define SPI2_GPIO GPIOB -#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB -#define SPI2_NSS_PIN Pin_12 -#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12 -#define SPI2_SCK_PIN Pin_13 -#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13 -#define SPI2_MISO_PIN Pin_14 -#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14 -#define SPI2_MOSI_PIN Pin_15 -#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15 - #define M25P16_CS_GPIO GPIOB #define M25P16_CS_PIN GPIO_Pin_12 #define M25P16_SPI_INSTANCE SPI2 diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index ef0eeaebbb6..39f145ae0db 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -44,6 +44,10 @@ #define USE_SPI #define USE_SPI_DEVICE_1 +#define SPI1_NSS_GPIO GPIOA +#define SPI1_NSS_PERIPHERAL RCC_AHBPeriph_GPIOA +#define SPI1_NSS_PIN GPIO_Pin_4 +#define SPI1_NSS_PIN_SOURCE GPIO_PinSource4 #define SPI1_GPIO GPIOB #define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB #define SPI1_SCK_PIN GPIO_Pin_3 diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index 02d1e84e69b..aebd5355198 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -195,10 +195,10 @@ #define S1W_RX_GPIO GPIOA #define S1W_RX_PIN GPIO_Pin_10 -// alternative defaults for AlienWii32 F1 target -#ifdef ALIENWII32 +// alternative defaults for AlienFlight F1 target +#ifdef ALIENFLIGHT #undef TARGET_BOARD_IDENTIFIER -#define TARGET_BOARD_IDENTIFIER "AWF1" // AlienWii32 F1. +#define TARGET_BOARD_IDENTIFIER "AWF1" // AlienFlight F1. #undef BOARD_HAS_VOLTAGE_DIVIDER #define HARDWARE_BIND_PLUG diff --git a/src/main/target/RMDO/target.h b/src/main/target/RMDO/target.h index f878e094ee8..34d3ab25f17 100644 --- a/src/main/target/RMDO/target.h +++ b/src/main/target/RMDO/target.h @@ -102,17 +102,6 @@ #define USE_SPI #define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 -#define SPI2_GPIO GPIOB -#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB -#define SPI2_NSS_PIN Pin_12 -#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12 -#define SPI2_SCK_PIN Pin_13 -#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13 -#define SPI2_MISO_PIN Pin_14 -#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14 -#define SPI2_MOSI_PIN Pin_15 -#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15 - #define M25P16_CS_GPIO GPIOB #define M25P16_CS_PIN GPIO_Pin_12 #define M25P16_SPI_INSTANCE SPI2 diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index 85eedde721a..6a8b9a72971 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -109,17 +109,6 @@ #define USE_SPI #define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 -#define SPI2_GPIO GPIOB -#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB -#define SPI2_NSS_PIN Pin_12 -#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12 -#define SPI2_SCK_PIN Pin_13 -#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13 -#define SPI2_MISO_PIN Pin_14 -#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14 -#define SPI2_MOSI_PIN Pin_15 -#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15 - #define M25P16_CS_GPIO GPIOB #define M25P16_CS_PIN GPIO_Pin_12 #define M25P16_SPI_INSTANCE SPI2 diff --git a/top_makefile b/top_makefile index 220ff15df69..4a3e572274f 100644 --- a/top_makefile +++ b/top_makefile @@ -32,8 +32,8 @@ clean_eustm32f103rc eustm32f103rc : opts := TARGET=EUSTM32F103RC clean_spracingf3 spracingf3 : opts := TARGET=SPRACINGF3 clean_port103r port103r : opts := TARGET=PORT103R clean_sparky sparky : opts := TARGET=SPARKY -clean_alienwiif1 alienwiif1 : opts := TARGET=ALIENWIIF1 -clean_alienwiif3 alienwiif3 : opts := TARGET=ALIENWIIF3 +clean_alienwiif1 alienwiif1 : opts := TARGET=ALIENFLIGHTF1 +clean_alienwiif3 alienwiif3 : opts := TARGET=ALIENFLIGHTF3 clean_colibri_race colibri_race : opts := TARGET=COLIBRI_RACE clean_lux_race lux_race : opts := TARGET=LUX_RACE clean_motolab motolab : opts := TARGET=MOTOLAB