From 3ddf8ee4624fbb736633ab759737e4c68db277b4 Mon Sep 17 00:00:00 2001
From: YI-BOYANG <46438966+YI-BOYANG@users.noreply.github.com>
Date: Thu, 10 Apr 2025 18:05:36 +0800
Subject: [PATCH 1/6] add GEPRC_TAKER_F405AIO
---
configs/GEPRC_TAKER_F405AIO/config.h | 110 +++++++++++++++++++++++++++
1 file changed, 110 insertions(+)
create mode 100644 configs/GEPRC_TAKER_F405AIO/config.h
diff --git a/configs/GEPRC_TAKER_F405AIO/config.h b/configs/GEPRC_TAKER_F405AIO/config.h
new file mode 100644
index 000000000..0b51fa775
--- /dev/null
+++ b/configs/GEPRC_TAKER_F405AIO/config.h
@@ -0,0 +1,110 @@
+/*
+ * 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 FC_TARGET_MCU STM32F405
+
+ #define BOARD_NAME GEPRC_TAKER_F405AIO
+ #define MANUFACTURER_ID GEPR
+
+ #define USE_ACC
+ #define USE_ACC_SPI_ICM42688P
+ #define USE_BARO
+ #define USE_BARO_DPS310
+ #define USE_GYRO
+ #define USE_GYRO_SPI_ICM42688P
+ #define USE_FLASH
+ #define USE_FLASH_W25Q128FV
+ #define USE_MAX7456
+
+ #define BEEPER_PIN PC13
+ #define MOTOR1_PIN PA8
+ #define MOTOR2_PIN PA9
+ #define MOTOR3_PIN PA10
+ #define MOTOR4_PIN PC8
+ #define RX_PPM_PIN PC7
+ #define LED_STRIP_PIN PB1
+ #define UART1_TX_PIN PB6
+ #define UART2_TX_PIN PA2
+ #define UART3_TX_PIN PC10
+ #define UART4_TX_PIN PA0
+ #define UART5_TX_PIN PC12
+ #define UART6_TX_PIN PC6
+ #define SOFTSERIAL1_TX_PIN PB2
+ #define UART1_RX_PIN PB7
+ #define UART2_RX_PIN PA3
+ #define UART3_RX_PIN PC11
+ #define UART4_RX_PIN PA1
+ #define UART5_RX_PIN PD2
+ #define UART6_RX_PIN PC7
+ #define SOFTSERIAL1_RX_PIN PC5
+ #define I2C1_SCL_PIN PB8
+ #define I2C2_SCL_PIN PB10
+ #define I2C1_SDA_PIN PB9
+ #define I2C2_SDA_PIN PB11
+ #define LED0_PIN PC14
+ #define LED1_PIN PC15
+ #define SPI1_SCK_PIN PA5
+ #define SPI2_SCK_PIN PB13
+ #define SPI3_SCK_PIN PB3
+ #define SPI1_SDI_PIN PA6
+ #define SPI2_SDI_PIN PB14
+ #define SPI3_SDI_PIN PB4
+ #define SPI1_SDO_PIN PA7
+ #define SPI2_SDO_PIN PB15
+ #define SPI3_SDO_PIN PB5
+ #define ADC_VBAT_PIN PC2
+ //#define ADC_RSSI_PIN PC2
+ #define ADC_CURR_PIN PC0
+ //#define PINIO1_PIN PA13
+ //#define PINIO2_PIN PA14
+ #define FLASH_CS_PIN PA4
+ #define MAX7456_SPI_CS_PIN PB12
+ #define GYRO_1_EXTI_PIN PC3
+ #define GYRO_1_CS_PIN PA15
+ #define USB_DETECT_PIN PC4
+
+ #define TIMER_PIN_MAPPING \
+ TIMER_PIN_MAP( 0, PC7 , 2, 0) \
+ TIMER_PIN_MAP( 1, PA8 , 1, 1) \
+ TIMER_PIN_MAP( 2, PA9 , 1, 1) \
+ TIMER_PIN_MAP( 3, PA10, 1, 1) \
+ TIMER_PIN_MAP( 4, PC8 , 2, 1)
+
+
+ #define ADC1_DMA_OPT 0
+
+ #define MAG_I2C_INSTANCE (I2CDEV_1)
+ #define BARO_I2C_INSTANCE (I2CDEV_1)
+
+ #define DEFAULT_BLACKBOX_DEVICE BLACKBOX_DEVICE_FLASH
+ #define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+ #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+ #define DEFAULT_CURRENT_METER_SCALE 179
+ #define BEEPER_INVERTED
+ #define SYSTEM_HSE_MHZ 8
+ #define MAX7456_SPI_INSTANCE SPI2
+ #define FLASH_SPI_INSTANCE SPI3
+ #define GYRO_1_SPI_INSTANCE SPI1
+ #define GYRO_1_ALIGN CW180_DEG
+ #define GYRO_1_ALIGN_YAW 2700
+
\ No newline at end of file
From 54d38efed8d5791eeaf3fde1a16982bd0384c431 Mon Sep 17 00:00:00 2001
From: YI-BOYANG <46438966+YI-BOYANG@users.noreply.github.com>
Date: Sun, 27 Apr 2025 11:03:07 +0800
Subject: [PATCH 2/6] Delete the softserial
---
configs/GEPRC_TAKER_F405AIO/config.h | 2 --
1 file changed, 2 deletions(-)
diff --git a/configs/GEPRC_TAKER_F405AIO/config.h b/configs/GEPRC_TAKER_F405AIO/config.h
index 0b51fa775..21878b1b3 100644
--- a/configs/GEPRC_TAKER_F405AIO/config.h
+++ b/configs/GEPRC_TAKER_F405AIO/config.h
@@ -49,14 +49,12 @@
#define UART4_TX_PIN PA0
#define UART5_TX_PIN PC12
#define UART6_TX_PIN PC6
- #define SOFTSERIAL1_TX_PIN PB2
#define UART1_RX_PIN PB7
#define UART2_RX_PIN PA3
#define UART3_RX_PIN PC11
#define UART4_RX_PIN PA1
#define UART5_RX_PIN PD2
#define UART6_RX_PIN PC7
- #define SOFTSERIAL1_RX_PIN PC5
#define I2C1_SCL_PIN PB8
#define I2C2_SCL_PIN PB10
#define I2C1_SDA_PIN PB9
From 1e15ebb7a7e138aea89555c10e8dc0d043efd788 Mon Sep 17 00:00:00 2001
From: YI-BOYANG <46438966+YI-BOYANG@users.noreply.github.com>
Date: Mon, 1 Sep 2025 18:20:11 +0800
Subject: [PATCH 3/6] Update configs/GEPRC_TAKER_F405AIO/config.h
Co-authored-by: Mark Haslinghuis
---
configs/GEPRC_TAKER_F405AIO/config.h | 1 -
1 file changed, 1 deletion(-)
diff --git a/configs/GEPRC_TAKER_F405AIO/config.h b/configs/GEPRC_TAKER_F405AIO/config.h
index 21878b1b3..8d1efd4ad 100644
--- a/configs/GEPRC_TAKER_F405AIO/config.h
+++ b/configs/GEPRC_TAKER_F405AIO/config.h
@@ -104,5 +104,4 @@
#define FLASH_SPI_INSTANCE SPI3
#define GYRO_1_SPI_INSTANCE SPI1
#define GYRO_1_ALIGN CW180_DEG
- #define GYRO_1_ALIGN_YAW 2700
\ No newline at end of file
From cac961c4feef987bf0057f75167db5d31922e685 Mon Sep 17 00:00:00 2001
From: YI-BOYANG <46438966+YI-BOYANG@users.noreply.github.com>
Date: Mon, 1 Sep 2025 18:20:27 +0800
Subject: [PATCH 4/6] Update configs/GEPRC_TAKER_F405AIO/config.h
Co-authored-by: Mark Haslinghuis
---
configs/GEPRC_TAKER_F405AIO/config.h | 3 +--
1 file changed, 1 insertion(+), 2 deletions(-)
diff --git a/configs/GEPRC_TAKER_F405AIO/config.h b/configs/GEPRC_TAKER_F405AIO/config.h
index 8d1efd4ad..0f1acbbbb 100644
--- a/configs/GEPRC_TAKER_F405AIO/config.h
+++ b/configs/GEPRC_TAKER_F405AIO/config.h
@@ -103,5 +103,4 @@
#define MAX7456_SPI_INSTANCE SPI2
#define FLASH_SPI_INSTANCE SPI3
#define GYRO_1_SPI_INSTANCE SPI1
- #define GYRO_1_ALIGN CW180_DEG
-
\ No newline at end of file
+ #define GYRO_1_ALIGN CW180_DEG
\ No newline at end of file
From 1372047857ad2541845623eece7458d2d9af00c5 Mon Sep 17 00:00:00 2001
From: YI-BOYANG <46438966+YI-BOYANG@users.noreply.github.com>
Date: Mon, 1 Sep 2025 18:22:23 +0800
Subject: [PATCH 5/6] Update configs/GEPRC_TAKER_F405AIO/config.h
Co-authored-by: Mark Haslinghuis
---
configs/GEPRC_TAKER_F405AIO/config.h | 4 ++--
1 file changed, 2 insertions(+), 2 deletions(-)
diff --git a/configs/GEPRC_TAKER_F405AIO/config.h b/configs/GEPRC_TAKER_F405AIO/config.h
index 0f1acbbbb..8481b4f70 100644
--- a/configs/GEPRC_TAKER_F405AIO/config.h
+++ b/configs/GEPRC_TAKER_F405AIO/config.h
@@ -91,8 +91,8 @@
#define ADC1_DMA_OPT 0
- #define MAG_I2C_INSTANCE (I2CDEV_1)
- #define BARO_I2C_INSTANCE (I2CDEV_1)
+#define BARO_I2C_INSTANCE I2CDEV_1
+#define MAG_I2C_INSTANCE I2CDEV_1
#define DEFAULT_BLACKBOX_DEVICE BLACKBOX_DEVICE_FLASH
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
From 4065badca6a50c2e7ab59d40ff39ad46e2428d72 Mon Sep 17 00:00:00 2001
From: YI-BOYANG <46438966+YI-BOYANG@users.noreply.github.com>
Date: Mon, 1 Sep 2025 18:27:10 +0800
Subject: [PATCH 6/6] delete LED1_PIN
---
configs/GEPRC_TAKER_F405AIO/config.h | 1 -
1 file changed, 1 deletion(-)
diff --git a/configs/GEPRC_TAKER_F405AIO/config.h b/configs/GEPRC_TAKER_F405AIO/config.h
index 8481b4f70..9bfc40c90 100644
--- a/configs/GEPRC_TAKER_F405AIO/config.h
+++ b/configs/GEPRC_TAKER_F405AIO/config.h
@@ -60,7 +60,6 @@
#define I2C1_SDA_PIN PB9
#define I2C2_SDA_PIN PB11
#define LED0_PIN PC14
- #define LED1_PIN PC15
#define SPI1_SCK_PIN PA5
#define SPI2_SCK_PIN PB13
#define SPI3_SCK_PIN PB3