From 255cf99b76c82a9b195aac48ce58bc99a65eab4c Mon Sep 17 00:00:00 2001 From: J Blackman Date: Thu, 1 Dec 2022 14:09:50 +1100 Subject: [PATCH] STM32H750 as a standard target (#11957) * STM32H750 * Adding additional files needed, and removing custom defaults. * Removed unnecessary define. * Corrected indentation * As per feedback * Aligned with target cleanup --- src/main/target/STM32H750/target.c | 21 ++++++++ src/main/target/STM32H750/target.h | 84 +++++++++++++++++++++++++++++ src/main/target/STM32H750/target.mk | 48 +++++++++++++++++ 3 files changed, 153 insertions(+) create mode 100644 src/main/target/STM32H750/target.c create mode 100644 src/main/target/STM32H750/target.h create mode 100644 src/main/target/STM32H750/target.mk diff --git a/src/main/target/STM32H750/target.c b/src/main/target/STM32H750/target.c new file mode 100644 index 0000000000..4eca06e63b --- /dev/null +++ b/src/main/target/STM32H750/target.c @@ -0,0 +1,21 @@ +/* + * 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 . + */ + +#include diff --git a/src/main/target/STM32H750/target.h b/src/main/target/STM32H750/target.h new file mode 100644 index 0000000000..d6a944a2e2 --- /dev/null +++ b/src/main/target/STM32H750/target.h @@ -0,0 +1,84 @@ +/* + * 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 "S750" + +#define USBD_PRODUCT_STRING "Betaflight STM32H750" + +#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_LP_UART1 + +#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 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 USE_I2C +#define I2C_FULL_RECONFIGURABILITY + +#define USE_BEEPER + +#ifdef USE_SDCARD +#define USE_SDCARD_SPI +#define USE_SDCARD_SDIO +#endif + +#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 CONFIG_IN_SDCARD diff --git a/src/main/target/STM32H750/target.mk b/src/main/target/STM32H750/target.mk new file mode 100644 index 0000000000..56502fc632 --- /dev/null +++ b/src/main/target/STM32H750/target.mk @@ -0,0 +1,48 @@ +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 + +H750xB_TARGETS += $(TARGET) + +HSE_VALUE = 8000000 + +ifneq ($(EXST),) +EXST = yes +EXST_ADJUST_VMA = 0x97CE0000 +endif + +ifneq ($(EXST),yes) +TARGET_FLASH_SIZE := 1024 +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750_1m.ld +endif + +FEATURES += VCP ONBOARDFLASH SDCARD_SDIO + +TARGET_SRC = \ + msc/usbd_storage_sd_spi.c \ + drivers/sdcard_spi.c \ + drivers/bus_quadspi_hal.c \ + drivers/bus_quadspi.c \ + $(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)