From 09beb47b6d37f1376acd4459ee04e21fb43c83de Mon Sep 17 00:00:00 2001 From: blckmn Date: Wed, 12 Oct 2022 07:35:50 +1100 Subject: [PATCH] Populate unified targets as separate target folders - note target folder is essentially the "platform" folder now. --- .../{STM32_UNIFIED => STM32F405}/target.c | 0 src/main/target/STM32F405/target.h | 182 ++++++++ src/main/target/STM32F405/target.mk | 34 ++ src/main/target/STM32F411/target.c | 22 + src/main/target/STM32F411/target.h | 158 +++++++ src/main/target/STM32F411/target.mk | 32 ++ src/main/target/STM32F411SX1280/target.c | 22 + src/main/target/STM32F411SX1280/target.h | 139 +++++++ src/main/target/STM32F411SX1280/target.mk | 21 + src/main/target/STM32F745/target.c | 22 + src/main/target/STM32F745/target.h | 183 +++++++++ .../{STM32_UNIFIED => STM32F745}/target.mk | 46 --- src/main/target/STM32F7X2/target.c | 22 + src/main/target/STM32F7X2/target.h | 159 +++++++ src/main/target/STM32F7X2/target.mk | 32 ++ src/main/target/STM32G47X/target.c | 22 + src/main/target/STM32G47X/target.h | 179 ++++++++ src/main/target/STM32G47X/target.mk | 32 ++ src/main/target/STM32H743/target.c | 22 + src/main/target/STM32H743/target.h | 187 +++++++++ src/main/target/STM32H743/target.mk | 34 ++ src/main/target/STM32_UNIFIED/STM32F405.mk | 0 src/main/target/STM32_UNIFIED/STM32F411.mk | 0 .../target/STM32_UNIFIED/STM32F411SX1280.mk | 0 src/main/target/STM32_UNIFIED/STM32F745.mk | 0 src/main/target/STM32_UNIFIED/STM32F7X2.mk | 0 src/main/target/STM32_UNIFIED/STM32G47X.mk | 0 src/main/target/STM32_UNIFIED/STM32H743.mk | 0 .../target/STM32_UNIFIED/STM32_UNIFIED.nomk | 0 src/main/target/STM32_UNIFIED/target.h | 387 ------------------ 30 files changed, 1504 insertions(+), 433 deletions(-) rename src/main/target/{STM32_UNIFIED => STM32F405}/target.c (100%) create mode 100644 src/main/target/STM32F405/target.h create mode 100644 src/main/target/STM32F405/target.mk create mode 100644 src/main/target/STM32F411/target.c create mode 100644 src/main/target/STM32F411/target.h create mode 100644 src/main/target/STM32F411/target.mk create mode 100644 src/main/target/STM32F411SX1280/target.c create mode 100644 src/main/target/STM32F411SX1280/target.h create mode 100644 src/main/target/STM32F411SX1280/target.mk create mode 100644 src/main/target/STM32F745/target.c create mode 100644 src/main/target/STM32F745/target.h rename src/main/target/{STM32_UNIFIED => STM32F745}/target.mk (54%) create mode 100644 src/main/target/STM32F7X2/target.c create mode 100644 src/main/target/STM32F7X2/target.h create mode 100644 src/main/target/STM32F7X2/target.mk create mode 100644 src/main/target/STM32G47X/target.c create mode 100644 src/main/target/STM32G47X/target.h create mode 100644 src/main/target/STM32G47X/target.mk create mode 100644 src/main/target/STM32H743/target.c create mode 100644 src/main/target/STM32H743/target.h create mode 100644 src/main/target/STM32H743/target.mk delete mode 100644 src/main/target/STM32_UNIFIED/STM32F405.mk delete mode 100644 src/main/target/STM32_UNIFIED/STM32F411.mk delete mode 100644 src/main/target/STM32_UNIFIED/STM32F411SX1280.mk delete mode 100644 src/main/target/STM32_UNIFIED/STM32F745.mk delete mode 100644 src/main/target/STM32_UNIFIED/STM32F7X2.mk delete mode 100644 src/main/target/STM32_UNIFIED/STM32G47X.mk delete mode 100644 src/main/target/STM32_UNIFIED/STM32H743.mk delete mode 100644 src/main/target/STM32_UNIFIED/STM32_UNIFIED.nomk delete mode 100644 src/main/target/STM32_UNIFIED/target.h diff --git a/src/main/target/STM32_UNIFIED/target.c b/src/main/target/STM32F405/target.c similarity index 100% rename from src/main/target/STM32_UNIFIED/target.c rename to src/main/target/STM32F405/target.c diff --git a/src/main/target/STM32F405/target.h b/src/main/target/STM32F405/target.h new file mode 100644 index 0000000000..d3f4ba01b3 --- /dev/null +++ b/src/main/target/STM32F405/target.h @@ -0,0 +1,182 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "S405" + +#define USBD_PRODUCT_STRING "Betaflight STM32F405" + +#define USE_I2C_DEVICE_1 +#define USE_I2C_DEVICE_2 +#define USE_I2C_DEVICE_3 + +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 +#define USE_UART5 +#define USE_UART6 + +#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 6) + +#define USE_INVERTER + +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_3 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff +#define TARGET_IO_PORTF 0xffff + + +// Treat the target as unified, and expect manufacturer id / board name +// to be supplied when the board is configured for the first time +#define USE_UNIFIED_TARGET + +#ifdef USE_RX_SPI +#define USE_RX_FRSKY_SPI_D +#define USE_RX_FRSKY_SPI_X +#define USE_RX_SFHSS_SPI +#define USE_RX_REDPINE_SPI +#define USE_RX_FRSKY_SPI_TELEMETRY +#define USE_RX_CC2500_SPI_PA_LNA +#define USE_RX_CC2500_SPI_DIVERSITY + +#define USE_RX_FLYSKY +#define USE_RX_FLYSKY_SPI_LED + +#define USE_RX_SPEKTRUM +#define USE_RX_SPEKTRUM_TELEMETRY +#endif + +#define USE_I2C +#define I2C_FULL_RECONFIGURABILITY + +#define USE_MAG +#define USE_BARO + +#define USE_BEEPER + +// MPU interrupt + +#define USE_ACC +#define USE_GYRO + +#define USE_ACC_MPU6500 +#define USE_GYRO_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACCGYRO_LSM6DSO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42605 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42605 +#define USE_ACC_SPI_ICM42688P + +#ifdef USE_MAG +#define USE_MAG_DATA_READY_SIGNAL +#define USE_MAG_HMC5883 +#define USE_MAG_SPI_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_LIS3MDL +#define USE_MAG_AK8963 +#define USE_MAG_MPU925X_AK8963 +#define USE_MAG_SPI_AK8963 +#define USE_MAG_AK8975 +#endif + +#ifdef USE_BARO +#define USE_BARO_MS5611 +#define USE_BARO_SPI_MS5611 +#define USE_BARO_BMP280 +#define USE_BARO_SPI_BMP280 +#define USE_BARO_BMP388 +#define USE_BARO_SPI_BMP388 +#define USE_BARO_LPS +#define USE_BARO_SPI_LPS +#define USE_BARO_QMP6988 +#define USE_BARO_SPI_QMP6988 +#define USE_BARO_DPS310 +#define USE_BARO_SPI_DPS310 +#endif + +#define USE_SDCARD +#define USE_SDCARD_SPI +#define USE_SDCARD_SDIO + +#define USE_FLASHFS +#define USE_FLASH_TOOLS +#define USE_FLASH_M25P16 +#define USE_FLASH_W25N01G // 1Gb NAND flash support +#define USE_FLASH_W25M // Stacked die support +#define USE_FLASH_W25M512 // 512Kb (256Kb x 2 stacked) NOR flash support +#define USE_FLASH_W25M02G // 2Gb (1Gb x 2 stacked) NAND flash support +#define USE_FLASH_W25Q128FV // 16MB Winbond 25Q128 + +#define USE_MAX7456 + +#define USE_SPI +#define SPI_FULL_RECONFIGURABILITY + +#define USE_VCP + +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 + +#define UNIFIED_SERIAL_PORT_COUNT 3 + +#define USE_USB_DETECT + +#define USE_ESCSERIAL + +#define USE_ADC + +#define USE_RX_SPI + +#define USE_CUSTOM_DEFAULTS + +#define USE_ACC_MPU6050 +#define USE_GYRO_MPU6050 +#define USE_ACCGYRO_BMI160 + +#define USE_BARO_BMP085 + +#define USE_VTX_RTC6705 +#define USE_VTX_RTC6705_SOFTSPI + +#define USE_TRANSPONDER + +#define USE_RANGEFINDER +#define USE_RANGEFINDER_HCSR04 +#define USE_RANGEFINDER_TF + +#define USE_RX_EXPRESSLRS +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 +#define USE_RX_SX1280 +#define USE_RX_SX127X diff --git a/src/main/target/STM32F405/target.mk b/src/main/target/STM32F405/target.mk new file mode 100644 index 0000000000..fd7a4a19ab --- /dev/null +++ b/src/main/target/STM32F405/target.mk @@ -0,0 +1,34 @@ +RX_SRC = \ + rx/cc2500_common.c \ + rx/cc2500_frsky_shared.c \ + rx/cc2500_frsky_d.c \ + rx/cc2500_frsky_x.c \ + rx/cc2500_sfhss.c \ + rx/cc2500_redpine.c \ + rx/a7105_flysky.c \ + rx/cyrf6936_spektrum.c \ + drivers/rx/expresslrs_driver.c \ + rx/expresslrs.c \ + rx/expresslrs_common.c \ + rx/expresslrs_telemetry.c \ + drivers/rx/rx_cc2500.c \ + drivers/rx/rx_a7105.c \ + drivers/rx/rx_cyrf6936.c \ + drivers/rx/rx_sx127x.c \ + drivers/rx/rx_sx1280.c \ + +F405_TARGETS += $(TARGET) + +CUSTOM_DEFAULTS_EXTENDED = yes + +FEATURES += VCP SDCARD_SPI SDCARD_SDIO ONBOARDFLASH + +TARGET_SRC = \ + $(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \ + $(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \ + $(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \ + $(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \ + drivers/max7456.c \ + drivers/vtx_rtc6705.c \ + drivers/vtx_rtc6705_soft_spi.c \ + $(RX_SRC) diff --git a/src/main/target/STM32F411/target.c b/src/main/target/STM32F411/target.c new file mode 100644 index 0000000000..a087e06bd2 --- /dev/null +++ b/src/main/target/STM32F411/target.c @@ -0,0 +1,22 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +// Needed to suppress the pedantic warning about an empty file +#include diff --git a/src/main/target/STM32F411/target.h b/src/main/target/STM32F411/target.h new file mode 100644 index 0000000000..6f99df8d91 --- /dev/null +++ b/src/main/target/STM32F411/target.h @@ -0,0 +1,158 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "S411" + +#define USBD_PRODUCT_STRING "Betaflight STM32F411" + +#define USE_I2C_DEVICE_1 +#define USE_I2C_DEVICE_2 +#define USE_I2C_DEVICE_3 + +#define USE_UART1 +#define USE_UART2 +#define USE_UART6 + +#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 3) + +#define USE_INVERTER + +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_3 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff + + +// Treat the target as unified, and expect manufacturer id / board name +// to be supplied when the board is configured for the first time +#define USE_UNIFIED_TARGET + +#ifdef USE_RX_SPI +#define USE_RX_FRSKY_SPI_D +#define USE_RX_FRSKY_SPI_X +#define USE_RX_SFHSS_SPI +#define USE_RX_REDPINE_SPI +#define USE_RX_FRSKY_SPI_TELEMETRY +#define USE_RX_CC2500_SPI_PA_LNA +#define USE_RX_CC2500_SPI_DIVERSITY + +#define USE_RX_FLYSKY +#define USE_RX_FLYSKY_SPI_LED + +#define USE_RX_SPEKTRUM +#define USE_RX_SPEKTRUM_TELEMETRY +#endif + +#define USE_I2C +#define I2C_FULL_RECONFIGURABILITY + +#define USE_MAG +#define USE_BARO + +#define USE_BEEPER + +// MPU interrupt + +#define USE_ACC +#define USE_GYRO + +#define USE_ACC_MPU6500 +#define USE_GYRO_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACCGYRO_LSM6DSO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42605 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42605 +#define USE_ACC_SPI_ICM42688P + +#ifdef USE_MAG +#define USE_MAG_DATA_READY_SIGNAL +#define USE_MAG_HMC5883 +#define USE_MAG_SPI_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_LIS3MDL +#define USE_MAG_AK8963 +#define USE_MAG_MPU925X_AK8963 +#define USE_MAG_SPI_AK8963 +#define USE_MAG_AK8975 +#endif + +#ifdef USE_BARO +#define USE_BARO_MS5611 +#define USE_BARO_SPI_MS5611 +#define USE_BARO_BMP280 +#define USE_BARO_SPI_BMP280 +#define USE_BARO_BMP388 +#define USE_BARO_SPI_BMP388 +#define USE_BARO_LPS +#define USE_BARO_SPI_LPS +#define USE_BARO_QMP6988 +#define USE_BARO_SPI_QMP6988 +#define USE_BARO_DPS310 +#define USE_BARO_SPI_DPS310 +#endif + +#define USE_SDCARD +#define USE_SDCARD_SPI +#define USE_SDCARD_SDIO + +#define USE_FLASHFS +#define USE_FLASH_TOOLS +#define USE_FLASH_M25P16 +#define USE_FLASH_W25N01G // 1Gb NAND flash support +#define USE_FLASH_W25M // Stacked die support +#define USE_FLASH_W25M512 // 512Kb (256Kb x 2 stacked) NOR flash support +#define USE_FLASH_W25M02G // 2Gb (1Gb x 2 stacked) NAND flash support +#define USE_FLASH_W25Q128FV // 16MB Winbond 25Q128 + +#define USE_MAX7456 + +#define USE_SPI +#define SPI_FULL_RECONFIGURABILITY + +#define USE_VCP + +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 + +#define UNIFIED_SERIAL_PORT_COUNT 3 + +#define USE_USB_DETECT + +#define USE_ESCSERIAL + +#define USE_ADC + +#define USE_RX_SPI + +#define USE_CUSTOM_DEFAULTS diff --git a/src/main/target/STM32F411/target.mk b/src/main/target/STM32F411/target.mk new file mode 100644 index 0000000000..8d917f0902 --- /dev/null +++ b/src/main/target/STM32F411/target.mk @@ -0,0 +1,32 @@ +RX_SRC = \ + rx/cc2500_common.c \ + rx/cc2500_frsky_shared.c \ + rx/cc2500_frsky_d.c \ + rx/cc2500_frsky_x.c \ + rx/cc2500_sfhss.c \ + rx/cc2500_redpine.c \ + rx/a7105_flysky.c \ + rx/cyrf6936_spektrum.c \ + drivers/rx/expresslrs_driver.c \ + rx/expresslrs.c \ + rx/expresslrs_common.c \ + rx/expresslrs_telemetry.c \ + drivers/rx/rx_cc2500.c \ + drivers/rx/rx_a7105.c \ + drivers/rx/rx_cyrf6936.c \ + drivers/rx/rx_sx127x.c \ + drivers/rx/rx_sx1280.c \ + +F411_TARGETS += $(TARGET) + +FEATURES += VCP SDCARD_SPI SDCARD_SDIO ONBOARDFLASH + +TARGET_SRC = \ + $(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \ + $(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \ + $(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \ + $(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \ + drivers/max7456.c \ + drivers/vtx_rtc6705.c \ + drivers/vtx_rtc6705_soft_spi.c \ + $(RX_SRC) diff --git a/src/main/target/STM32F411SX1280/target.c b/src/main/target/STM32F411SX1280/target.c new file mode 100644 index 0000000000..a087e06bd2 --- /dev/null +++ b/src/main/target/STM32F411SX1280/target.c @@ -0,0 +1,22 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +// Needed to suppress the pedantic warning about an empty file +#include diff --git a/src/main/target/STM32F411SX1280/target.h b/src/main/target/STM32F411SX1280/target.h new file mode 100644 index 0000000000..ad31159553 --- /dev/null +++ b/src/main/target/STM32F411SX1280/target.h @@ -0,0 +1,139 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#pragma once +#define TARGET_BOARD_IDENTIFIER "S4SX" + +#define USBD_PRODUCT_STRING "Betaflight STM32F411SX1280" + +#define USE_UART1 +#define USE_UART2 +#define USE_UART6 + +#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 3) + +#define USE_INVERTER + +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_3 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff + +// Treat the target as unified, and expect manufacturer id / board name +// to be supplied when the board is configured for the first time +#define USE_UNIFIED_TARGET + +#define DEFAULT_RX_FEATURE FEATURE_RX_SPI +#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_EXPRESSLRS + +#define USE_RX_EXPRESSLRS +#define USE_RX_EXPRESSLRS_TELEMETRY +#define USE_RX_SX1280 +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 +#define RX_CHANNELS_AETR + +#define USE_BEEPER + +// MPU interrupt + +#define USE_ACC +#define USE_GYRO + +#define USE_ACC_MPU6500 +#define USE_GYRO_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACCGYRO_LSM6DSO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42605 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42605 +#define USE_ACC_SPI_ICM42688P + +#ifdef USE_MAG +#define USE_MAG_DATA_READY_SIGNAL +#define USE_MAG_HMC5883 +#define USE_MAG_SPI_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_LIS3MDL +#define USE_MAG_AK8963 +#define USE_MAG_MPU925X_AK8963 +#define USE_MAG_SPI_AK8963 +#define USE_MAG_AK8975 +#endif + +#ifdef USE_BARO +#define USE_BARO_MS5611 +#define USE_BARO_SPI_MS5611 +#define USE_BARO_BMP280 +#define USE_BARO_SPI_BMP280 +#define USE_BARO_BMP388 +#define USE_BARO_SPI_BMP388 +#define USE_BARO_LPS +#define USE_BARO_SPI_LPS +#define USE_BARO_QMP6988 +#define USE_BARO_SPI_QMP6988 +#define USE_BARO_DPS310 +#define USE_BARO_SPI_DPS310 +#endif + +#define USE_SDCARD +#define USE_SDCARD_SPI +#define USE_SDCARD_SDIO + +#define USE_FLASHFS +#define USE_FLASH_TOOLS +#define USE_FLASH_M25P16 +#define USE_FLASH_W25N01G // 1Gb NAND flash support +#define USE_FLASH_W25M // Stacked die support +#define USE_FLASH_W25M512 // 512Kb (256Kb x 2 stacked) NOR flash support +#define USE_FLASH_W25M02G // 2Gb (1Gb x 2 stacked) NAND flash support +#define USE_FLASH_W25Q128FV // 16MB Winbond 25Q128 + +#define USE_MAX7456 + +#define USE_SPI +#define SPI_FULL_RECONFIGURABILITY + +#define USE_VCP + +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 + +#define UNIFIED_SERIAL_PORT_COUNT 3 + +#define USE_USB_DETECT + +#define USE_ESCSERIAL + +#define USE_ADC + +#define USE_RX_SPI + +#define USE_CUSTOM_DEFAULTS diff --git a/src/main/target/STM32F411SX1280/target.mk b/src/main/target/STM32F411SX1280/target.mk new file mode 100644 index 0000000000..ec48b82856 --- /dev/null +++ b/src/main/target/STM32F411SX1280/target.mk @@ -0,0 +1,21 @@ +RX_SRC = \ + drivers/rx/expresslrs_driver.c \ + drivers/rx/rx_sx127x.c \ + drivers/rx/rx_sx1280.c \ + rx/expresslrs_telemetry.c \ + rx/expresslrs_common.c \ + rx/expresslrs.c + +F411_TARGETS += $(TARGET) + +FEATURES += VCP SDCARD_SPI SDCARD_SDIO ONBOARDFLASH + +TARGET_SRC = \ + $(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \ + $(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \ + $(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \ + $(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \ + drivers/max7456.c \ + drivers/vtx_rtc6705.c \ + drivers/vtx_rtc6705_soft_spi.c \ + $(RX_SRC) diff --git a/src/main/target/STM32F745/target.c b/src/main/target/STM32F745/target.c new file mode 100644 index 0000000000..a087e06bd2 --- /dev/null +++ b/src/main/target/STM32F745/target.c @@ -0,0 +1,22 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +// Needed to suppress the pedantic warning about an empty file +#include diff --git a/src/main/target/STM32F745/target.h b/src/main/target/STM32F745/target.h new file mode 100644 index 0000000000..36cb4ffe5e --- /dev/null +++ b/src/main/target/STM32F745/target.h @@ -0,0 +1,183 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "S745" + +#define USBD_PRODUCT_STRING "Betaflight STM32F745" + +#define USE_I2C_DEVICE_1 +#define USE_I2C_DEVICE_2 +#define USE_I2C_DEVICE_3 +#define USE_I2C_DEVICE_4 + +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 +#define USE_UART5 +#define USE_UART6 +#define USE_UART7 +#define USE_UART8 + +#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 8) + +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_3 +#define USE_SPI_DEVICE_4 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff +#define TARGET_IO_PORTF 0xffff + +// Treat the target as unified, and expect manufacturer id / board name +// to be supplied when the board is configured for the first time +#define USE_UNIFIED_TARGET + +#ifdef USE_RX_SPI +#define USE_RX_FRSKY_SPI_D +#define USE_RX_FRSKY_SPI_X +#define USE_RX_SFHSS_SPI +#define USE_RX_REDPINE_SPI +#define USE_RX_FRSKY_SPI_TELEMETRY +#define USE_RX_CC2500_SPI_PA_LNA +#define USE_RX_CC2500_SPI_DIVERSITY + +#define USE_RX_FLYSKY +#define USE_RX_FLYSKY_SPI_LED + +#define USE_RX_SPEKTRUM +#define USE_RX_SPEKTRUM_TELEMETRY +#endif + +#define USE_I2C +#define I2C_FULL_RECONFIGURABILITY + +#define USE_MAG +#define USE_BARO + +#define USE_BEEPER + +// MPU interrupt + +#define USE_ACC +#define USE_GYRO + +#define USE_ACC_MPU6500 +#define USE_GYRO_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACCGYRO_LSM6DSO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42605 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42605 +#define USE_ACC_SPI_ICM42688P + +#ifdef USE_MAG +#define USE_MAG_DATA_READY_SIGNAL +#define USE_MAG_HMC5883 +#define USE_MAG_SPI_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_LIS3MDL +#define USE_MAG_AK8963 +#define USE_MAG_MPU925X_AK8963 +#define USE_MAG_SPI_AK8963 +#define USE_MAG_AK8975 +#endif + +#ifdef USE_BARO +#define USE_BARO_MS5611 +#define USE_BARO_SPI_MS5611 +#define USE_BARO_BMP280 +#define USE_BARO_SPI_BMP280 +#define USE_BARO_BMP388 +#define USE_BARO_SPI_BMP388 +#define USE_BARO_LPS +#define USE_BARO_SPI_LPS +#define USE_BARO_QMP6988 +#define USE_BARO_SPI_QMP6988 +#define USE_BARO_DPS310 +#define USE_BARO_SPI_DPS310 +#endif + +#define USE_SDCARD +#define USE_SDCARD_SPI +#define USE_SDCARD_SDIO + +#define USE_FLASHFS +#define USE_FLASH_TOOLS +#define USE_FLASH_M25P16 +#define USE_FLASH_W25N01G // 1Gb NAND flash support +#define USE_FLASH_W25M // Stacked die support +#define USE_FLASH_W25M512 // 512Kb (256Kb x 2 stacked) NOR flash support +#define USE_FLASH_W25M02G // 2Gb (1Gb x 2 stacked) NAND flash support +#define USE_FLASH_W25Q128FV // 16MB Winbond 25Q128 + +#define USE_MAX7456 + +#define USE_SPI +#define SPI_FULL_RECONFIGURABILITY + +#define USE_VCP + +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 + +#define UNIFIED_SERIAL_PORT_COUNT 3 + +#define USE_USB_DETECT + +#define USE_ESCSERIAL + +#define USE_ADC + +#define USE_RX_SPI + +#define USE_CUSTOM_DEFAULTS + +#define USE_ACC_MPU6050 +#define USE_GYRO_MPU6050 +#define USE_ACCGYRO_BMI160 + +#define USE_BARO_BMP085 + +#define USE_VTX_RTC6705 +#define USE_VTX_RTC6705_SOFTSPI + +#define USE_TRANSPONDER + +#define USE_RANGEFINDER +#define USE_RANGEFINDER_HCSR04 +#define USE_RANGEFINDER_TF + +#define USE_RX_EXPRESSLRS +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 +#define USE_RX_SX1280 +#define USE_RX_SX127X diff --git a/src/main/target/STM32_UNIFIED/target.mk b/src/main/target/STM32F745/target.mk similarity index 54% rename from src/main/target/STM32_UNIFIED/target.mk rename to src/main/target/STM32F745/target.mk index c5e6a16f17..df8070e93c 100644 --- a/src/main/target/STM32_UNIFIED/target.mk +++ b/src/main/target/STM32F745/target.mk @@ -17,57 +17,11 @@ RX_SRC = \ drivers/rx/rx_sx127x.c \ drivers/rx/rx_sx1280.c \ -ifeq ($(TARGET), STM32F405) -F405_TARGETS += $(TARGET) - -else -ifeq ($(TARGET), STM32F411) -F411_TARGETS += $(TARGET) - -else -ifeq ($(TARGET), STM32F411SX1280) -F411_TARGETS += $(TARGET) -RX_SRC = \ - drivers/rx/expresslrs_driver.c \ - drivers/rx/rx_sx127x.c \ - drivers/rx/rx_sx1280.c \ - rx/expresslrs_telemetry.c \ - rx/expresslrs_common.c \ - rx/expresslrs.c \ - -else -ifeq ($(TARGET), STM32F7X2) -F7X2RE_TARGETS += $(TARGET) - -else -ifeq ($(TARGET), STM32F745) F7X5XG_TARGETS += $(TARGET) -else -ifeq ($(TARGET), STM32G47X) -G47X_TARGETS += $(TARGET) - -else # STM32H743 -H743xI_TARGETS += $(TARGET) - -endif -endif -endif -endif -endif -endif - -ifeq ($(TARGET), $(filter $(TARGET), STM32F405 STM32F745 STM32H743)) -# Use a full block (16 kB) of flash for custom defaults - with 1 MB flash we have more than we know how to use anyway - CUSTOM_DEFAULTS_EXTENDED = yes -endif -ifeq ($(TARGET), STM32G47X) -FEATURES += VCP SDCARD_SPI ONBOARDFLASH -else FEATURES += VCP SDCARD_SPI SDCARD_SDIO ONBOARDFLASH -endif TARGET_SRC = \ $(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \ diff --git a/src/main/target/STM32F7X2/target.c b/src/main/target/STM32F7X2/target.c new file mode 100644 index 0000000000..a087e06bd2 --- /dev/null +++ b/src/main/target/STM32F7X2/target.c @@ -0,0 +1,22 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +// Needed to suppress the pedantic warning about an empty file +#include diff --git a/src/main/target/STM32F7X2/target.h b/src/main/target/STM32F7X2/target.h new file mode 100644 index 0000000000..26cf76de1f --- /dev/null +++ b/src/main/target/STM32F7X2/target.h @@ -0,0 +1,159 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "S7X2" + +#define USBD_PRODUCT_STRING "Betaflight STM32F7x2" + +#define USE_I2C_DEVICE_1 +#define USE_I2C_DEVICE_2 +#define USE_I2C_DEVICE_3 + +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 +#define USE_UART5 +#define USE_UART6 + +#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 6) + +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_3 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff +#define TARGET_IO_PORTF 0xffff + +// Treat the target as unified, and expect manufacturer id / board name +// to be supplied when the board is configured for the first time +#define USE_UNIFIED_TARGET + +#ifdef USE_RX_SPI +#define USE_RX_FRSKY_SPI_D +#define USE_RX_FRSKY_SPI_X +#define USE_RX_SFHSS_SPI +#define USE_RX_REDPINE_SPI +#define USE_RX_FRSKY_SPI_TELEMETRY +#define USE_RX_CC2500_SPI_PA_LNA +#define USE_RX_CC2500_SPI_DIVERSITY + +#define USE_RX_FLYSKY +#define USE_RX_FLYSKY_SPI_LED + +#define USE_RX_SPEKTRUM +#define USE_RX_SPEKTRUM_TELEMETRY +#endif + +#define USE_I2C +#define I2C_FULL_RECONFIGURABILITY + +#define USE_MAG +#define USE_BARO + +#define USE_BEEPER + +// MPU interrupt + +#define USE_ACC +#define USE_GYRO + +#define USE_ACC_MPU6500 +#define USE_GYRO_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACCGYRO_LSM6DSO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42605 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42605 +#define USE_ACC_SPI_ICM42688P + +#ifdef USE_MAG +#define USE_MAG_DATA_READY_SIGNAL +#define USE_MAG_HMC5883 +#define USE_MAG_SPI_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_LIS3MDL +#define USE_MAG_AK8963 +#define USE_MAG_MPU925X_AK8963 +#define USE_MAG_SPI_AK8963 +#define USE_MAG_AK8975 +#endif + +#ifdef USE_BARO +#define USE_BARO_MS5611 +#define USE_BARO_SPI_MS5611 +#define USE_BARO_BMP280 +#define USE_BARO_SPI_BMP280 +#define USE_BARO_BMP388 +#define USE_BARO_SPI_BMP388 +#define USE_BARO_LPS +#define USE_BARO_SPI_LPS +#define USE_BARO_QMP6988 +#define USE_BARO_SPI_QMP6988 +#define USE_BARO_DPS310 +#define USE_BARO_SPI_DPS310 +#endif + +#define USE_SDCARD +#define USE_SDCARD_SPI +#define USE_SDCARD_SDIO + +#define USE_FLASHFS +#define USE_FLASH_TOOLS +#define USE_FLASH_M25P16 +#define USE_FLASH_W25N01G // 1Gb NAND flash support +#define USE_FLASH_W25M // Stacked die support +#define USE_FLASH_W25M512 // 512Kb (256Kb x 2 stacked) NOR flash support +#define USE_FLASH_W25M02G // 2Gb (1Gb x 2 stacked) NAND flash support +#define USE_FLASH_W25Q128FV // 16MB Winbond 25Q128 + +#define USE_MAX7456 + +#define USE_SPI +#define SPI_FULL_RECONFIGURABILITY + +#define USE_VCP + +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 + +#define UNIFIED_SERIAL_PORT_COUNT 3 + +#define USE_USB_DETECT + +#define USE_ESCSERIAL + +#define USE_ADC + +#define USE_RX_SPI + +#define USE_CUSTOM_DEFAULTS diff --git a/src/main/target/STM32F7X2/target.mk b/src/main/target/STM32F7X2/target.mk new file mode 100644 index 0000000000..2e6512cb7f --- /dev/null +++ b/src/main/target/STM32F7X2/target.mk @@ -0,0 +1,32 @@ +RX_SRC = \ + rx/cc2500_common.c \ + rx/cc2500_frsky_shared.c \ + rx/cc2500_frsky_d.c \ + rx/cc2500_frsky_x.c \ + rx/cc2500_sfhss.c \ + rx/cc2500_redpine.c \ + rx/a7105_flysky.c \ + rx/cyrf6936_spektrum.c \ + drivers/rx/expresslrs_driver.c \ + rx/expresslrs.c \ + rx/expresslrs_common.c \ + rx/expresslrs_telemetry.c \ + drivers/rx/rx_cc2500.c \ + drivers/rx/rx_a7105.c \ + drivers/rx/rx_cyrf6936.c \ + drivers/rx/rx_sx127x.c \ + drivers/rx/rx_sx1280.c \ + + +F7X2RE_TARGETS += $(TARGET) +FEATURES += VCP SDCARD_SPI SDCARD_SDIO ONBOARDFLASH + +TARGET_SRC = \ + $(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \ + $(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \ + $(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \ + $(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \ + drivers/max7456.c \ + drivers/vtx_rtc6705.c \ + drivers/vtx_rtc6705_soft_spi.c \ + $(RX_SRC) diff --git a/src/main/target/STM32G47X/target.c b/src/main/target/STM32G47X/target.c new file mode 100644 index 0000000000..a087e06bd2 --- /dev/null +++ b/src/main/target/STM32G47X/target.c @@ -0,0 +1,22 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +// Needed to suppress the pedantic warning about an empty file +#include diff --git a/src/main/target/STM32G47X/target.h b/src/main/target/STM32G47X/target.h new file mode 100644 index 0000000000..32b4cdcaba --- /dev/null +++ b/src/main/target/STM32G47X/target.h @@ -0,0 +1,179 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#pragma once +#define TARGET_BOARD_IDENTIFIER "SG47" + +#define USBD_PRODUCT_STRING "Betaflight STM32G47x" + +#define USE_I2C_DEVICE_1 +#define USE_I2C_DEVICE_2 +#define USE_I2C_DEVICE_3 +#define USE_I2C_DEVICE_4 + +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 +#define USE_UART5 +#define USE_LPUART1 + +#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 6) + +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_3 +#define USE_SPI_DEVICE_4 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff +#define TARGET_IO_PORTF 0xffff + +// Treat the target as unified, and expect manufacturer id / board name +// to be supplied when the board is configured for the first time +#define USE_UNIFIED_TARGET + +#ifdef USE_RX_SPI +#define USE_RX_FRSKY_SPI_D +#define USE_RX_FRSKY_SPI_X +#define USE_RX_SFHSS_SPI +#define USE_RX_REDPINE_SPI +#define USE_RX_FRSKY_SPI_TELEMETRY +#define USE_RX_CC2500_SPI_PA_LNA +#define USE_RX_CC2500_SPI_DIVERSITY + +#define USE_RX_FLYSKY +#define USE_RX_FLYSKY_SPI_LED + +#define USE_RX_SPEKTRUM +#define USE_RX_SPEKTRUM_TELEMETRY +#endif + +#define USE_I2C +#define I2C_FULL_RECONFIGURABILITY + +#define USE_MAG +#define USE_BARO + +#define USE_BEEPER + +// MPU interrupt + +#define USE_ACC +#define USE_GYRO + +#define USE_ACC_MPU6500 +#define USE_GYRO_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACCGYRO_LSM6DSO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42605 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42605 +#define USE_ACC_SPI_ICM42688P + +#ifdef USE_MAG +#define USE_MAG_DATA_READY_SIGNAL +#define USE_MAG_HMC5883 +#define USE_MAG_SPI_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_LIS3MDL +#define USE_MAG_AK8963 +#define USE_MAG_MPU925X_AK8963 +#define USE_MAG_SPI_AK8963 +#define USE_MAG_AK8975 +#endif + +#ifdef USE_BARO +#define USE_BARO_MS5611 +#define USE_BARO_SPI_MS5611 +#define USE_BARO_BMP280 +#define USE_BARO_SPI_BMP280 +#define USE_BARO_BMP388 +#define USE_BARO_SPI_BMP388 +#define USE_BARO_LPS +#define USE_BARO_SPI_LPS +#define USE_BARO_QMP6988 +#define USE_BARO_SPI_QMP6988 +#define USE_BARO_DPS310 +#define USE_BARO_SPI_DPS310 +#endif + +#define USE_SDCARD +#define USE_SDCARD_SPI + +#define USE_FLASHFS +#define USE_FLASH_TOOLS +#define USE_FLASH_M25P16 +#define USE_FLASH_W25N01G // 1Gb NAND flash support +#define USE_FLASH_W25M // Stacked die support +#define USE_FLASH_W25M512 // 512Kb (256Kb x 2 stacked) NOR flash support +#define USE_FLASH_W25M02G // 2Gb (1Gb x 2 stacked) NAND flash support +#define USE_FLASH_W25Q128FV // 16MB Winbond 25Q128 + +#define USE_MAX7456 + +#define USE_SPI +#define SPI_FULL_RECONFIGURABILITY + +#define USE_VCP + +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 + +#define UNIFIED_SERIAL_PORT_COUNT 3 + +#define USE_USB_DETECT + +#define USE_ESCSERIAL + +#define USE_ADC + +#define USE_RX_SPI + +#define USE_CUSTOM_DEFAULTS + +#define USE_ACC_MPU6050 +#define USE_GYRO_MPU6050 +#define USE_ACCGYRO_BMI160 + +#define USE_BARO_BMP085 + +#define USE_VTX_RTC6705 +#define USE_VTX_RTC6705_SOFTSPI + +#define USE_TRANSPONDER + +#define USE_RANGEFINDER +#define USE_RANGEFINDER_HCSR04 +#define USE_RANGEFINDER_TF + +#define USE_RX_EXPRESSLRS +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 +#define USE_RX_SX1280 +#define USE_RX_SX127X diff --git a/src/main/target/STM32G47X/target.mk b/src/main/target/STM32G47X/target.mk new file mode 100644 index 0000000000..b421ac91e8 --- /dev/null +++ b/src/main/target/STM32G47X/target.mk @@ -0,0 +1,32 @@ +RX_SRC = \ + rx/cc2500_common.c \ + rx/cc2500_frsky_shared.c \ + rx/cc2500_frsky_d.c \ + rx/cc2500_frsky_x.c \ + rx/cc2500_sfhss.c \ + rx/cc2500_redpine.c \ + rx/a7105_flysky.c \ + rx/cyrf6936_spektrum.c \ + drivers/rx/expresslrs_driver.c \ + rx/expresslrs.c \ + rx/expresslrs_common.c \ + rx/expresslrs_telemetry.c \ + drivers/rx/rx_cc2500.c \ + drivers/rx/rx_a7105.c \ + drivers/rx/rx_cyrf6936.c \ + drivers/rx/rx_sx127x.c \ + drivers/rx/rx_sx1280.c \ + +G47X_TARGETS += $(TARGET) + +FEATURES += VCP SDCARD_SPI ONBOARDFLASH + +TARGET_SRC = \ + $(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \ + $(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \ + $(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \ + $(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \ + drivers/max7456.c \ + drivers/vtx_rtc6705.c \ + drivers/vtx_rtc6705_soft_spi.c \ + $(RX_SRC) diff --git a/src/main/target/STM32H743/target.c b/src/main/target/STM32H743/target.c new file mode 100644 index 0000000000..a087e06bd2 --- /dev/null +++ b/src/main/target/STM32H743/target.c @@ -0,0 +1,22 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +// Needed to suppress the pedantic warning about an empty file +#include diff --git a/src/main/target/STM32H743/target.h b/src/main/target/STM32H743/target.h new file mode 100644 index 0000000000..c40ee67325 --- /dev/null +++ b/src/main/target/STM32H743/target.h @@ -0,0 +1,187 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "SH74" + +#define USBD_PRODUCT_STRING "Betaflight STM32H743" + +#define USE_I2C_DEVICE_1 +#define USE_I2C_DEVICE_2 +#define USE_I2C_DEVICE_3 +#define USE_I2C_DEVICE_4 + +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 +#define USE_UART5 +#define USE_UART6 +#define USE_UART7 +#define USE_UART8 +#define USE_LPUART1 + +#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 9) + +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_3 +#define USE_SPI_DEVICE_4 +#define USE_SPI_DEVICE_5 +#define USE_SPI_DEVICE_6 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff +#define TARGET_IO_PORTF 0xffff +#define TARGET_IO_PORTG 0xffff + +// Treat the target as unified, and expect manufacturer id / board name +// to be supplied when the board is configured for the first time +#define USE_UNIFIED_TARGET + +#ifdef USE_RX_SPI +#define USE_RX_FRSKY_SPI_D +#define USE_RX_FRSKY_SPI_X +#define USE_RX_SFHSS_SPI +#define USE_RX_REDPINE_SPI +#define USE_RX_FRSKY_SPI_TELEMETRY +#define USE_RX_CC2500_SPI_PA_LNA +#define USE_RX_CC2500_SPI_DIVERSITY + +#define USE_RX_FLYSKY +#define USE_RX_FLYSKY_SPI_LED + +#define USE_RX_SPEKTRUM +#define USE_RX_SPEKTRUM_TELEMETRY +#endif + +#define USE_I2C +#define I2C_FULL_RECONFIGURABILITY + +#define USE_MAG +#define USE_BARO + +#define USE_BEEPER + +// MPU interrupt + +#define USE_ACC +#define USE_GYRO + +#define USE_ACC_MPU6500 +#define USE_GYRO_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACCGYRO_LSM6DSO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42605 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42605 +#define USE_ACC_SPI_ICM42688P + +#ifdef USE_MAG +#define USE_MAG_DATA_READY_SIGNAL +#define USE_MAG_HMC5883 +#define USE_MAG_SPI_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_LIS3MDL +#define USE_MAG_AK8963 +#define USE_MAG_MPU925X_AK8963 +#define USE_MAG_SPI_AK8963 +#define USE_MAG_AK8975 +#endif + +#ifdef USE_BARO +#define USE_BARO_MS5611 +#define USE_BARO_SPI_MS5611 +#define USE_BARO_BMP280 +#define USE_BARO_SPI_BMP280 +#define USE_BARO_BMP388 +#define USE_BARO_SPI_BMP388 +#define USE_BARO_LPS +#define USE_BARO_SPI_LPS +#define USE_BARO_QMP6988 +#define USE_BARO_SPI_QMP6988 +#define USE_BARO_DPS310 +#define USE_BARO_SPI_DPS310 +#endif + +#define USE_SDCARD +#define USE_SDCARD_SPI +#define USE_SDCARD_SDIO + +#define USE_FLASHFS +#define USE_FLASH_TOOLS +#define USE_FLASH_M25P16 +#define USE_FLASH_W25N01G // 1Gb NAND flash support +#define USE_FLASH_W25M // Stacked die support +#define USE_FLASH_W25M512 // 512Kb (256Kb x 2 stacked) NOR flash support +#define USE_FLASH_W25M02G // 2Gb (1Gb x 2 stacked) NAND flash support +#define USE_FLASH_W25Q128FV // 16MB Winbond 25Q128 + +#define USE_MAX7456 + +#define USE_SPI +#define SPI_FULL_RECONFIGURABILITY + +#define USE_VCP + +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 + +#define UNIFIED_SERIAL_PORT_COUNT 3 + +#define USE_USB_DETECT + +#define USE_ESCSERIAL + +#define USE_ADC + +#define USE_RX_SPI + +#define USE_CUSTOM_DEFAULTS + +#define USE_ACC_MPU6050 +#define USE_GYRO_MPU6050 +#define USE_ACCGYRO_BMI160 + +#define USE_BARO_BMP085 + +#define USE_VTX_RTC6705 +#define USE_VTX_RTC6705_SOFTSPI + +#define USE_TRANSPONDER + +#define USE_RANGEFINDER +#define USE_RANGEFINDER_HCSR04 +#define USE_RANGEFINDER_TF + +#define USE_RX_EXPRESSLRS +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 +#define USE_RX_SX1280 +#define USE_RX_SX127X diff --git a/src/main/target/STM32H743/target.mk b/src/main/target/STM32H743/target.mk new file mode 100644 index 0000000000..2ed32c8132 --- /dev/null +++ b/src/main/target/STM32H743/target.mk @@ -0,0 +1,34 @@ +RX_SRC = \ + rx/cc2500_common.c \ + rx/cc2500_frsky_shared.c \ + rx/cc2500_frsky_d.c \ + rx/cc2500_frsky_x.c \ + rx/cc2500_sfhss.c \ + rx/cc2500_redpine.c \ + rx/a7105_flysky.c \ + rx/cyrf6936_spektrum.c \ + drivers/rx/expresslrs_driver.c \ + rx/expresslrs.c \ + rx/expresslrs_common.c \ + rx/expresslrs_telemetry.c \ + drivers/rx/rx_cc2500.c \ + drivers/rx/rx_a7105.c \ + drivers/rx/rx_cyrf6936.c \ + drivers/rx/rx_sx127x.c \ + drivers/rx/rx_sx1280.c \ + +H743xI_TARGETS += $(TARGET) + +CUSTOM_DEFAULTS_EXTENDED = yes + +FEATURES += VCP SDCARD_SPI SDCARD_SDIO ONBOARDFLASH + +TARGET_SRC = \ + $(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \ + $(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \ + $(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \ + $(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \ + drivers/max7456.c \ + drivers/vtx_rtc6705.c \ + drivers/vtx_rtc6705_soft_spi.c \ + $(RX_SRC) diff --git a/src/main/target/STM32_UNIFIED/STM32F405.mk b/src/main/target/STM32_UNIFIED/STM32F405.mk deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/src/main/target/STM32_UNIFIED/STM32F411.mk b/src/main/target/STM32_UNIFIED/STM32F411.mk deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/src/main/target/STM32_UNIFIED/STM32F411SX1280.mk b/src/main/target/STM32_UNIFIED/STM32F411SX1280.mk deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/src/main/target/STM32_UNIFIED/STM32F745.mk b/src/main/target/STM32_UNIFIED/STM32F745.mk deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/src/main/target/STM32_UNIFIED/STM32F7X2.mk b/src/main/target/STM32_UNIFIED/STM32F7X2.mk deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/src/main/target/STM32_UNIFIED/STM32G47X.mk b/src/main/target/STM32_UNIFIED/STM32G47X.mk deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/src/main/target/STM32_UNIFIED/STM32H743.mk b/src/main/target/STM32_UNIFIED/STM32H743.mk deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/src/main/target/STM32_UNIFIED/STM32_UNIFIED.nomk b/src/main/target/STM32_UNIFIED/STM32_UNIFIED.nomk deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/src/main/target/STM32_UNIFIED/target.h b/src/main/target/STM32_UNIFIED/target.h deleted file mode 100644 index fe9d94d880..0000000000 --- a/src/main/target/STM32_UNIFIED/target.h +++ /dev/null @@ -1,387 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software 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 and Betaflight are distributed in the hope that they - * 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 this software. - * - * If not, see . - */ - -#pragma once - -#if defined(STM32F405) -#define TARGET_BOARD_IDENTIFIER "S405" - -#define USBD_PRODUCT_STRING "Betaflight STM32F405" - -#define USE_I2C_DEVICE_1 -#define USE_I2C_DEVICE_2 -#define USE_I2C_DEVICE_3 - -#define USE_UART1 -#define USE_UART2 -#define USE_UART3 -#define USE_UART4 -#define USE_UART5 -#define USE_UART6 - -#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 6) - -#define USE_INVERTER - -#define USE_SPI_DEVICE_1 -#define USE_SPI_DEVICE_2 -#define USE_SPI_DEVICE_3 - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0xffff - -#elif defined(STM32F411) -#define TARGET_BOARD_IDENTIFIER "S411" - -#define USBD_PRODUCT_STRING "Betaflight STM32F411" - -#define USE_I2C_DEVICE_1 -#define USE_I2C_DEVICE_2 -#define USE_I2C_DEVICE_3 - -#define USE_UART1 -#define USE_UART2 -#define USE_UART6 - -#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 3) - -#define USE_INVERTER - -#define USE_SPI_DEVICE_1 -#define USE_SPI_DEVICE_2 -#define USE_SPI_DEVICE_3 - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff - -#elif defined(STM32F411SX1280) -#define TARGET_BOARD_IDENTIFIER "S4SX" - -#define USBD_PRODUCT_STRING "Betaflight STM32F411SX1280" - -#define USE_UART1 -#define USE_UART2 -#define USE_UART6 - -#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 3) - -#define USE_INVERTER - -#define USE_SPI_DEVICE_1 -#define USE_SPI_DEVICE_2 -#define USE_SPI_DEVICE_3 - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff - -#elif defined(STM32F7X2) -#define TARGET_BOARD_IDENTIFIER "S7X2" - -#define USBD_PRODUCT_STRING "Betaflight STM32F7x2" - -#define USE_I2C_DEVICE_1 -#define USE_I2C_DEVICE_2 -#define USE_I2C_DEVICE_3 - -#define USE_UART1 -#define USE_UART2 -#define USE_UART3 -#define USE_UART4 -#define USE_UART5 -#define USE_UART6 - -#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 6) - -#define USE_SPI_DEVICE_1 -#define USE_SPI_DEVICE_2 -#define USE_SPI_DEVICE_3 - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0xffff - -#elif defined(STM32F745) -#define TARGET_BOARD_IDENTIFIER "S745" - -#define USBD_PRODUCT_STRING "Betaflight STM32F745" - -#define USE_I2C_DEVICE_1 -#define USE_I2C_DEVICE_2 -#define USE_I2C_DEVICE_3 -#define USE_I2C_DEVICE_4 - -#define USE_UART1 -#define USE_UART2 -#define USE_UART3 -#define USE_UART4 -#define USE_UART5 -#define USE_UART6 -#define USE_UART7 -#define USE_UART8 - -#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 8) - -#define USE_SPI_DEVICE_1 -#define USE_SPI_DEVICE_2 -#define USE_SPI_DEVICE_3 -#define USE_SPI_DEVICE_4 - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0xffff - -#elif defined(STM32G47X) -#define TARGET_BOARD_IDENTIFIER "SG47" - -#define USBD_PRODUCT_STRING "Betaflight STM32G47x" - -#define USE_I2C_DEVICE_1 -#define USE_I2C_DEVICE_2 -#define USE_I2C_DEVICE_3 -#define USE_I2C_DEVICE_4 - -#define USE_UART1 -#define USE_UART2 -#define USE_UART3 -#define USE_UART4 -#define USE_UART5 -#define USE_LPUART1 - -#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 6) - -#define USE_SPI_DEVICE_1 -#define USE_SPI_DEVICE_2 -#define USE_SPI_DEVICE_3 -#define USE_SPI_DEVICE_4 - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0xffff - -#elif defined(STM32H743) -#define TARGET_BOARD_IDENTIFIER "SH74" - -#define USBD_PRODUCT_STRING "Betaflight STM32H743" - -#define USE_I2C_DEVICE_1 -#define USE_I2C_DEVICE_2 -#define USE_I2C_DEVICE_3 -#define USE_I2C_DEVICE_4 - -#define USE_UART1 -#define USE_UART2 -#define USE_UART3 -#define USE_UART4 -#define USE_UART5 -#define USE_UART6 -#define USE_UART7 -#define USE_UART8 -#define USE_LPUART1 - -#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 9) - -#define USE_SPI_DEVICE_1 -#define USE_SPI_DEVICE_2 -#define USE_SPI_DEVICE_3 -#define USE_SPI_DEVICE_4 -#define USE_SPI_DEVICE_5 -#define USE_SPI_DEVICE_6 - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0xffff -#define TARGET_IO_PORTG 0xffff - -#elif !defined(UNIT_TEST) - -#error "No resources defined for this Unified Target." - -#endif - -// Treat the target as unified, and expect manufacturer id / board name -// to be supplied when the board is configured for the first time -#define USE_UNIFIED_TARGET - -// Only enable ELRS support on STM32F411SX1280 target -#if defined(STM32F411SX1280) -#define DEFAULT_RX_FEATURE FEATURE_RX_SPI -#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_EXPRESSLRS - -#define USE_RX_EXPRESSLRS -#define USE_RX_EXPRESSLRS_TELEMETRY -#define USE_RX_SX1280 -#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 -#define RX_CHANNELS_AETR - -#else // STM32F411SX1280 -#define USE_RX_FRSKY_SPI_D -#define USE_RX_FRSKY_SPI_X -#define USE_RX_SFHSS_SPI -#define USE_RX_REDPINE_SPI -#define USE_RX_FRSKY_SPI_TELEMETRY -#define USE_RX_CC2500_SPI_PA_LNA -#define USE_RX_CC2500_SPI_DIVERSITY - -#define USE_RX_FLYSKY -#define USE_RX_FLYSKY_SPI_LED - -#define USE_RX_SPEKTRUM -#define USE_RX_SPEKTRUM_TELEMETRY - -#define USE_I2C -#define I2C_FULL_RECONFIGURABILITY - -#define USE_MAG -#define USE_BARO - -#endif // STM32F411SX1280 - -#define USE_BEEPER - -// MPU interrupt - -#define USE_ACC -#define USE_GYRO - -#define USE_ACC_MPU6500 -#define USE_GYRO_MPU6500 -#define USE_ACC_SPI_MPU6000 -#define USE_GYRO_SPI_MPU6000 -#define USE_ACC_SPI_MPU6500 -#define USE_GYRO_SPI_MPU6500 -#define USE_ACC_SPI_ICM20689 -#define USE_GYRO_SPI_ICM20689 -#define USE_ACCGYRO_LSM6DSO -#define USE_ACCGYRO_BMI270 -#define USE_GYRO_SPI_ICM42605 -#define USE_GYRO_SPI_ICM42688P -#define USE_ACC_SPI_ICM42605 -#define USE_ACC_SPI_ICM42688P - -#ifdef USE_MAG -#define USE_MAG_DATA_READY_SIGNAL -#define USE_MAG_HMC5883 -#define USE_MAG_SPI_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_LIS3MDL -#define USE_MAG_AK8963 -#define USE_MAG_MPU925X_AK8963 -#define USE_MAG_SPI_AK8963 -#define USE_MAG_AK8975 -#endif - -#ifdef USE_BARO -#define USE_BARO_MS5611 -#define USE_BARO_SPI_MS5611 -#define USE_BARO_BMP280 -#define USE_BARO_SPI_BMP280 -#define USE_BARO_BMP388 -#define USE_BARO_SPI_BMP388 -#define USE_BARO_LPS -#define USE_BARO_SPI_LPS -#define USE_BARO_QMP6988 -#define USE_BARO_SPI_QMP6988 -#define USE_BARO_DPS310 -#define USE_BARO_SPI_DPS310 -#endif - -#define USE_SDCARD -#define USE_SDCARD_SPI -#if !defined(STM32G4) -// G4 support needs fixing -#define USE_SDCARD_SDIO -#endif - -#define USE_FLASHFS -#define USE_FLASH_TOOLS -#define USE_FLASH_M25P16 -#define USE_FLASH_W25N01G // 1Gb NAND flash support -#define USE_FLASH_W25M // Stacked die support -#define USE_FLASH_W25M512 // 512Kb (256Kb x 2 stacked) NOR flash support -#define USE_FLASH_W25M02G // 2Gb (1Gb x 2 stacked) NAND flash support -#define USE_FLASH_W25Q128FV // 16MB Winbond 25Q128 - -#define USE_MAX7456 - -#define USE_SPI -#define SPI_FULL_RECONFIGURABILITY - -#define USE_VCP - -#define USE_SOFTSERIAL1 -#define USE_SOFTSERIAL2 - -#define UNIFIED_SERIAL_PORT_COUNT 3 - -#define USE_USB_DETECT - -#define USE_ESCSERIAL - -#define USE_ADC - -#define USE_RX_SPI - -#define USE_CUSTOM_DEFAULTS - -// Additional drivers included for targets with > 512KB of flash -#if (TARGET_FLASH_SIZE > 512) -#define USE_ACC_MPU6050 -#define USE_GYRO_MPU6050 -#define USE_ACCGYRO_BMI160 - -#define USE_BARO_BMP085 - -#define USE_VTX_RTC6705 -#define USE_VTX_RTC6705_SOFTSPI - -#define USE_TRANSPONDER - -#define USE_RANGEFINDER -#define USE_RANGEFINDER_HCSR04 -#define USE_RANGEFINDER_TF - -#define USE_RX_EXPRESSLRS -#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 -#define USE_RX_SX1280 -#define USE_RX_SX127X - -#endif