diff --git a/Makefile b/Makefile index 0570301915..186633ed5e 100644 --- a/Makefile +++ b/Makefile @@ -126,7 +126,7 @@ endif # default xtal value HSE_VALUE ?= 8000000 -CI_TARGETS := $(BASE_TARGETS) $(filter CRAZYBEEF4SX1280 CRAZYBEEF4FR IFLIGHT_BLITZ_F722, $(BASE_CONFIGS)) +CI_TARGETS := $(BASE_TARGETS) $(filter CRAZYBEEF4SX1280 CRAZYBEEF4FR IFLIGHT_BLITZ_F722 NUCLEOF446, $(BASE_CONFIGS)) include $(ROOT)/src/main/target/$(TARGET)/target.mk REVISION := norevision diff --git a/src/main/target/STM32F446/target.h b/src/main/target/STM32F446/target.h new file mode 100644 index 0000000000..3cbe022c6e --- /dev/null +++ b/src/main/target/STM32F446/target.h @@ -0,0 +1,78 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "S446" + +#define USBD_PRODUCT_STRING "Betaflight STM32F446" + +#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 UNIFIED_SERIAL_PORT_COUNT 3 +#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 & ~(BIT(14)|BIT(13))) +#define TARGET_IO_PORTB (0xffff & ~(BIT(2))) +#define TARGET_IO_PORTC (0xffff & ~(BIT(15)|BIT(14)|BIT(13))) +#define TARGET_IO_PORTD BIT(2) + +// #define USABLE_TIMER_CHANNEL_COUNT 8 +// #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8)) + +#define USE_I2C +#define I2C_FULL_RECONFIGURABILITY + +#ifdef USE_SDCARD +#define USE_SDCARD_SPI +#define USE_SDCARD_SDIO +#endif + +#define USE_SPI +#define SPI_FULL_RECONFIGURABILITY +#define USE_SPI_DMA_ENABLE_EARLY + +#define USE_VCP + +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 + +#define USE_USB_DETECT + +#define USE_ESCSERIAL + +#define USE_ADC + +#define USE_EXTI + +#define FLASH_PAGE_SIZE ((uint32_t)0x4000) // 16K sectors diff --git a/src/main/target/STM32F446/target.mk b/src/main/target/STM32F446/target.mk new file mode 100644 index 0000000000..004e43c5d3 --- /dev/null +++ b/src/main/target/STM32F446/target.mk @@ -0,0 +1,16 @@ +TARGET_MCU := STM32F446xx +TARGET_MCU_FAMILY := STM32F4 + +TARGET_SRC = \ + drivers/accgyro/accgyro_mpu6500.c \ + drivers/accgyro/accgyro_spi_mpu6500.c \ + drivers/accgyro/accgyro_spi_mpu9250.c \ + drivers/accgyro/accgyro_virtual.c \ + drivers/barometer/barometer_virtual.c \ + drivers/compass/compass_virtual.c \ + drivers/rx/rx_nrf24l01.c \ + rx/nrf24_cx10.c \ + rx/nrf24_inav.c \ + rx/nrf24_h8_3d.c \ + rx/nrf24_syma.c \ + rx/nrf24_v202.c