From 764ea65b3ae2c052a431359db1c77ea8258fbb5f Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Fri, 30 Sep 2022 15:53:57 -0500
Subject: [PATCH 01/22] ICM426xx - very dont know
FOXEERF722V4
ICM_42688P & ICM_42605 ; CAUTION / really no idea if this is anything good
more ICM_42688P & ICM_42605 ; CAUTION / really no idea if this is anything good
FOXEERF745V3_AIO
---
src/main/drivers/accgyro/accgyro_mpu.c | 14 ++
src/main/drivers/accgyro/accgyro_mpu.h | 4 +
.../drivers/accgyro/accgyro_spi_icm426xx.c | 194 ++++++++++++++++++
.../drivers/accgyro/accgyro_spi_icm426xx.h | 36 ++++
.../drivers/accgyro/accgyro_spi_mpu6500.c | 6 +
src/main/pg/bus_spi.c | 3 +
src/main/sensors/acceleration.c | 26 +++
src/main/sensors/acceleration.h | 2 +
src/main/sensors/gyro.c | 26 +++
src/main/sensors/gyro.h | 2 +
src/main/target/FOXEERF722V4/target.c | 45 ++++
src/main/target/FOXEERF722V4/target.h | 154 ++++++++++++++
src/main/target/FOXEERF722V4/target.mk | 14 ++
src/main/target/FOXEERF745V3_AIO/target.c | 40 ++++
src/main/target/FOXEERF745V3_AIO/target.h | 161 +++++++++++++++
src/main/target/FOXEERF745V3_AIO/target.mk | 12 ++
16 files changed, 739 insertions(+)
create mode 100644 src/main/drivers/accgyro/accgyro_spi_icm426xx.c
create mode 100644 src/main/drivers/accgyro/accgyro_spi_icm426xx.h
create mode 100644 src/main/target/FOXEERF722V4/target.c
create mode 100644 src/main/target/FOXEERF722V4/target.h
create mode 100644 src/main/target/FOXEERF722V4/target.mk
create mode 100644 src/main/target/FOXEERF745V3_AIO/target.c
create mode 100644 src/main/target/FOXEERF745V3_AIO/target.h
create mode 100644 src/main/target/FOXEERF745V3_AIO/target.mk
diff --git a/src/main/drivers/accgyro/accgyro_mpu.c b/src/main/drivers/accgyro/accgyro_mpu.c
index 498536f8c2..7f9e96c772 100644
--- a/src/main/drivers/accgyro/accgyro_mpu.c
+++ b/src/main/drivers/accgyro/accgyro_mpu.c
@@ -55,6 +55,7 @@
#include "drivers/accgyro/accgyro_spi_bmi160.h"
#include "drivers/accgyro/accgyro_spi_icm20649.h"
#include "drivers/accgyro/accgyro_spi_icm20689.h"
+#include "drivers/accgyro/accgyro_spi_icm426xx.h"
#include "drivers/accgyro/accgyro_spi_mpu6000.h"
#include "drivers/accgyro/accgyro_spi_mpu6500.h"
#include "drivers/accgyro/accgyro_spi_mpu9250.h"
@@ -365,6 +366,19 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro) {
return true;
}
#endif
+#ifdef USE_GYRO_SPI_ICM42688P
+#ifdef ICM42688P_SPI_INSTANCE
+ spiBusSetInstance(&gyro->bus, ICM42688P_SPI_INSTANCE);
+#endif
+#ifdef ICM42688P_CS_PIN
+ gyro->bus.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(ICM42688P_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin;
+#endif
+ sensor = icm426xxSpiDetect(&gyro->bus);
+ if (sensor != MPU_NONE) {
+ gyro->mpuDetectionResult.sensor = sensor;
+ return true;
+ }
+#endif
#ifdef USE_ACCGYRO_BMI160
#ifndef USE_DUAL_GYRO
spiBusSetInstance(&gyro->bus, BMI160_SPI_INSTANCE);
diff --git a/src/main/drivers/accgyro/accgyro_mpu.h b/src/main/drivers/accgyro/accgyro_mpu.h
index 550f05fe81..6c045ccd44 100644
--- a/src/main/drivers/accgyro/accgyro_mpu.h
+++ b/src/main/drivers/accgyro/accgyro_mpu.h
@@ -47,6 +47,8 @@
#define ICM20608G_WHO_AM_I_CONST (0xAF)
#define ICM20649_WHO_AM_I_CONST (0xE1)
#define ICM20689_WHO_AM_I_CONST (0x98)
+#define ICM42605_WHO_AM_I_CONST (0x42)
+#define ICM42688P_WHO_AM_I_CONST (0x47)
// RA = Register Address
@@ -214,6 +216,8 @@ typedef enum {
ICM_20608_SPI,
ICM_20649_SPI,
ICM_20689_SPI,
+ ICM_42605_SPI,
+ ICM_42688P_SPI,
BMI_160_SPI,
IMUF_9001_SPI,
} mpuSensor_e;
diff --git a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c
new file mode 100644
index 0000000000..6d837775de
--- /dev/null
+++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c
@@ -0,0 +1,194 @@
+/*
+ * 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
+#include
+#include
+
+#include "platform.h"
+
+#include "common/axis.h"
+#include "common/maths.h"
+
+#include "drivers/accgyro/accgyro.h"
+#include "drivers/accgyro/accgyro_mpu.h"
+#include "drivers/accgyro/accgyro_spi_icm426xx.h"
+#include "drivers/bus_spi.h"
+#include "drivers/exti.h"
+#include "drivers/io.h"
+#include "drivers/sensor.h"
+#include "drivers/time.h"
+
+
+// 24 MHz max SPI frequency
+#define ICM426XX_MAX_SPI_CLK_HZ 24000000
+
+#define ICM426XX_RA_PWR_MGMT0 0x4E
+
+#define ICM426XX_PWR_MGMT0_ACCEL_MODE_LN (3 << 0)
+#define ICM426XX_PWR_MGMT0_GYRO_MODE_LN (3 << 2)
+#define ICM426XX_PWR_MGMT0_TEMP_DISABLE_OFF (0 << 5)
+#define ICM426XX_PWR_MGMT0_TEMP_DISABLE_ON (1 << 5)
+
+#define ICM426XX_RA_GYRO_CONFIG0 0x4F
+#define ICM426XX_RA_ACCEL_CONFIG0 0x50
+
+#define ICM426XX_RA_GYRO_ACCEL_CONFIG0 0x52
+
+#define ICM426XX_ACCEL_UI_FILT_BW_LOW_LATENCY (14 << 4)
+#define ICM426XX_GYRO_UI_FILT_BW_LOW_LATENCY (14 << 0)
+
+#define ICM426XX_RA_GYRO_DATA_X1 0x25
+#define ICM426XX_RA_ACCEL_DATA_X1 0x1F
+
+#define ICM426XX_RA_INT_CONFIG 0x14
+#define ICM426XX_INT1_MODE_PULSED (0 << 2)
+#define ICM426XX_INT1_MODE_LATCHED (1 << 2)
+#define ICM426XX_INT1_DRIVE_CIRCUIT_OD (0 << 1)
+#define ICM426XX_INT1_DRIVE_CIRCUIT_PP (1 << 1)
+#define ICM426XX_INT1_POLARITY_ACTIVE_LOW (0 << 0)
+#define ICM426XX_INT1_POLARITY_ACTIVE_HIGH (1 << 0)
+
+#define ICM426XX_RA_INT_CONFIG0 0x63
+#define ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR ((0 << 5) || (0 << 4))
+#define ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR_DUPLICATE ((0 << 5) || (0 << 4)) // duplicate settings in datasheet, Rev 1.2.
+#define ICM426XX_UI_DRDY_INT_CLEAR_ON_F1BR ((1 << 5) || (0 << 4))
+#define ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR_AND_F1BR ((1 << 5) || (1 << 4))
+
+#define ICM426XX_RA_INT_CONFIG1 0x64
+#define ICM426XX_INT_ASYNC_RESET_BIT 4
+#define ICM426XX_INT_TDEASSERT_DISABLE_BIT 5
+#define ICM426XX_INT_TDEASSERT_ENABLED (0 << ICM426XX_INT_TDEASSERT_DISABLE_BIT)
+#define ICM426XX_INT_TDEASSERT_DISABLED (1 << ICM426XX_INT_TDEASSERT_DISABLE_BIT)
+#define ICM426XX_INT_TPULSE_DURATION_BIT 6
+#define ICM426XX_INT_TPULSE_DURATION_100 (0 << ICM426XX_INT_TPULSE_DURATION_BIT)
+#define ICM426XX_INT_TPULSE_DURATION_8 (1 << ICM426XX_INT_TPULSE_DURATION_BIT)
+
+
+#define ICM426XX_RA_INT_SOURCE0 0x65
+#define ICM426XX_UI_DRDY_INT1_EN_DISABLED (0 << 3)
+#define ICM426XX_UI_DRDY_INT1_EN_ENABLED (1 << 3)
+
+
+static void icm426xxSpiInit(const busDevice_t *bus) {
+ static bool hardwareInitialised = false;
+ if (hardwareInitialised) {
+ return;
+ }
+#ifndef USE_DUAL_GYRO
+ IOInit(bus->busdev_u.spi.csnPin, OWNER_MPU_CS, 0);
+ IOConfigGPIO(bus->busdev_u.spi.csnPin, SPI_IO_CS_CFG);
+ IOHi(bus->busdev_u.spi.csnPin);
+#endif
+ spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_STANDARD);
+ hardwareInitialised = true;
+}
+
+uint8_t icm426xxSpiDetect(const busDevice_t *bus) {
+ icm426xxSpiInit(bus);
+ spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_INITIALIZATION); //low speed
+ spiBusWriteRegister(bus, MPU_RA_PWR_MGMT_1, ICM426xx_BIT_RESET);
+ uint8_t icmDetected = MPU_NONE;
+ uint8_t attemptsRemaining = 20;
+ do {
+ delay(150);
+ const uint8_t whoAmI = spiBusReadRegister(bus, MPU_RA_WHO_AM_I);
+ switch (whoAmI) {
+ case ICM42605_WHO_AM_I_CONST:
+ icmDetected = ICM_42605_SPI;
+ break;
+ case ICM42688P_WHO_AM_I_CONST:
+ icmDetected = ICM_42688P_SPI;
+ break;
+ default:
+ icmDetected = MPU_NONE;
+ break;
+ }
+ if (icmDetected != MPU_NONE) {
+ break;
+ }
+ if (!attemptsRemaining) {
+ return MPU_NONE;
+ }
+ } while (attemptsRemaining--);
+ spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_STANDARD);
+ return icmDetected;
+}
+
+void icm426xxAccInit(accDev_t *acc) {
+ acc->acc_1G = 512 * 4;
+}
+
+bool icm426xxSpiAccDetect(accDev_t *acc) {
+ switch (acc->mpuDetectionResult.sensor) {
+ case ICM_42605_SPI:
+ case ICM_42688P_SPI:
+ break;
+ default:
+ return false;
+ }
+ acc->initFn = icm426xxAccInit;
+ acc->readFn = mpuAccRead;
+ return true;
+}
+
+void icm426xxGyroInit(gyroDev_t *gyro) {
+ mpuGyroInit(gyro);
+ spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATION);
+ spiBusWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, ICM426xx_BIT_RESET);
+ delay(100);
+ spiBusWriteRegister(&gyro->bus, MPU_RA_SIGNAL_PATH_RESET, 0x03);
+ delay(100);
+// spiBusWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, 0);
+// delay(100);
+ spiBusWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, INV_CLK_PLL);
+ delay(15);
+ spiBusWriteRegister(&gyro->bus, MPU_RA_GYRO_CONFIG, (3 - INV_FSR_2000DPS) << 5 | mpuGyroFCHOICE(gyro));
+ delay(15);
+ spiBusWriteRegister(&gyro->bus, MPU_RA_ACCEL_CONFIG, (3 - INV_FSR_16G) << 5);
+ delay(15);
+ spiBusWriteRegister(&gyro->bus, MPU_RA_CONFIG, mpuGyroDLPF(gyro));
+ delay(15);
+ spiBusWriteRegister(&gyro->bus, MPU_RA_SMPLRT_DIV, gyro->mpuDividerDrops); // Get Divider Drops
+ delay(100);
+ // Data ready interrupt configuration
+// spiBusWriteRegister(&gyro->bus, MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 0 << 1 | 0 << 0); // INT_ANYRD_2CLEAR, BYPASS_EN
+ spiBusWriteRegister(&gyro->bus, MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR, BYPASS_EN
+ delay(15);
+#ifdef USE_MPU_DATA_READY_SIGNAL
+ spiBusWriteRegister(&gyro->bus, MPU_RA_INT_ENABLE, 0x01); // RAW_RDY_EN interrupt enable
+#endif
+ spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_STANDARD);
+}
+
+bool icm426xxSpiGyroDetect(gyroDev_t *gyro) {
+ switch (gyro->mpuDetectionResult.sensor) {
+ case ICM_42605_SPI:
+ case ICM_42688P_SPI:
+ break;
+ default:
+ return false;
+ }
+ gyro->initFn = icm426xxGyroInit;
+ gyro->readFn = mpuGyroReadSPI;
+ // 16.4 dps/lsb scalefactor
+ gyro->scale = 1.0f / 16.4f;
+ return true;
+}
diff --git a/src/main/drivers/accgyro/accgyro_spi_icm426xx.h b/src/main/drivers/accgyro/accgyro_spi_icm426xx.h
new file mode 100644
index 0000000000..842fe6626e
--- /dev/null
+++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.h
@@ -0,0 +1,36 @@
+/*
+ * 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
+
+#include "drivers/bus.h"
+
+#define ICM426xx_BIT_RESET (0x80)
+
+bool icm426xxAccDetect(accDev_t *acc);
+bool icm426xxGyroDetect(gyroDev_t *gyro);
+
+void icm426xxAccInit(accDev_t *acc);
+void icm426xxGyroInit(gyroDev_t *gyro);
+
+uint8_t icm426xxSpiDetect(const busDevice_t *dev);
+
+bool icm426xxSpiAccDetect(accDev_t *acc);
+bool icm426xxSpiGyroDetect(gyroDev_t *gyro);
\ No newline at end of file
diff --git a/src/main/drivers/accgyro/accgyro_spi_mpu6500.c b/src/main/drivers/accgyro/accgyro_spi_mpu6500.c
index a39d053d7a..86bca64388 100644
--- a/src/main/drivers/accgyro/accgyro_spi_mpu6500.c
+++ b/src/main/drivers/accgyro/accgyro_spi_mpu6500.c
@@ -69,6 +69,12 @@ uint8_t mpu6500SpiDetect(const busDevice_t *bus) {
case ICM20608G_WHO_AM_I_CONST:
mpuDetected = ICM_20608_SPI;
break;
+ case ICM42605_WHO_AM_I_CONST:
+ mpuDetected = ICM_42605_SPI;
+ break;
+ case ICM42688P_WHO_AM_I_CONST:
+ mpuDetected = ICM_42688P_SPI;
+ break;
default:
mpuDetected = MPU_NONE;
}
diff --git a/src/main/pg/bus_spi.c b/src/main/pg/bus_spi.c
index a51b0e9378..3f8beca26c 100644
--- a/src/main/pg/bus_spi.c
+++ b/src/main/pg/bus_spi.c
@@ -91,6 +91,9 @@ ioTag_t preinitIPUList[SPI_PREINIT_IPU_COUNT] = {
#ifdef ICM20689_CS_PIN
IO_TAG(ICM20689_CS_PIN),
#endif
+#ifdef ICM42688P_CS_PIN
+ IO_TAG(ICM42688P_CS_PIN),
+#endif
#ifdef BMI160_CS_PIN
IO_TAG(BMI160_CS_PIN),
#endif
diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c
index 1d1f08b132..86873b177a 100644
--- a/src/main/sensors/acceleration.c
+++ b/src/main/sensors/acceleration.c
@@ -48,6 +48,7 @@
#include "drivers/accgyro/accgyro_spi_mpu6000.h"
#include "drivers/accgyro/accgyro_spi_mpu6500.h"
#include "drivers/accgyro/accgyro_spi_mpu9250.h"
+#include "drivers/accgyro/accgyro_spi_icm426xx.h"
#ifdef USE_ACC_ADXL345
#include "drivers/accgyro_legacy/accgyro_adxl345.h"
@@ -298,6 +299,31 @@ bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse) {
}
FALLTHROUGH;
#endif
+#if defined(USE_ACC_SPI_ICM42605) || defined(USE_ACC_SPI_ICM42688P)
+ case ACC_ICM42605:
+ case ACC_ICM42688P:
+ if (icm426xxSpiAccDetect(dev)) {
+ switch (dev->mpuDetectionResult.sensor) {
+ case ICM_42605_SPI:
+ accHardware = ACC_ICM42605;
+#ifdef ACC_ICM42605_ALIGN
+ dev->accAlign = ACC_ICM42605_ALIGN;
+#endif
+ break;
+ case ICM_42688P_SPI:
+ accHardware = ACC_ICM42688P;
+#ifdef ACC_ICM42688P_ALIGN
+ dev->accAlign = ACC_ICM42688P_ALIGN;
+#endif
+ break;
+ default:
+ accHardware = ACC_NONE;
+ break;
+ }
+ break;
+ }
+ FALLTHROUGH;
+#endif
#ifdef USE_FAKE_ACC
case ACC_FAKE:
if (fakeAccDetect(dev)) {
diff --git a/src/main/sensors/acceleration.h b/src/main/sensors/acceleration.h
index 778263ee37..b448d2419b 100644
--- a/src/main/sensors/acceleration.h
+++ b/src/main/sensors/acceleration.h
@@ -47,6 +47,8 @@ typedef enum {
ACC_ICM20608G,
ACC_ICM20649,
ACC_ICM20689,
+ ACC_ICM42605,
+ ACC_ICM42688P,
ACC_BMI160,
ACC_IMUF9001,
ACC_FAKE
diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c
index 60d6a62df3..ba0466bd33 100644
--- a/src/main/sensors/gyro.c
+++ b/src/main/sensors/gyro.c
@@ -49,6 +49,7 @@
#include "drivers/accgyro/accgyro_spi_mpu6000.h"
#include "drivers/accgyro/accgyro_spi_mpu6500.h"
#include "drivers/accgyro/accgyro_spi_mpu9250.h"
+#include "drivers/accgyro/accgyro_spi_icm426xx.h"
#ifdef USE_GYRO_L3G4200D
#include "drivers/accgyro_legacy/accgyro_l3g4200d.h"
@@ -496,6 +497,31 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev) {
}
FALLTHROUGH;
#endif
+#if defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P)
+ case GYRO_ICM42605:
+ case GYRO_ICM42688P:
+ if (icm426xxSpiGyroDetect(dev)) {
+ switch (dev->mpuDetectionResult.sensor) {
+ case ICM_42605_SPI:
+ gyroHardware = GYRO_ICM42605;
+#ifdef GYRO_ICM42605_ALIGN
+ dev->gyroAlign = GYRO_ICM42605_ALIGN;
+#endif
+ break;
+ case ICM_42688P_SPI:
+ gyroHardware = GYRO_ICM42688P;
+#ifdef GYRO_ICM42688P_ALIGN
+ dev->gyroAlign = GYRO_ICM42688P_ALIGN;
+#endif
+ break;
+ default:
+ gyroHardware = GYRO_NONE;
+ break;
+ }
+ break;
+ }
+ FALLTHROUGH;
+#endif
#ifdef USE_ACCGYRO_BMI160
case GYRO_BMI160:
if (bmi160SpiGyroDetect(dev)) {
diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h
index 1bbb627a89..4387c872e3 100644
--- a/src/main/sensors/gyro.h
+++ b/src/main/sensors/gyro.h
@@ -53,6 +53,8 @@ typedef enum {
GYRO_ICM20608G,
GYRO_ICM20649,
GYRO_ICM20689,
+ GYRO_ICM42605,
+ GYRO_ICM42688P,
GYRO_BMI160,
GYRO_IMUF9001,
GYRO_FAKE
diff --git a/src/main/target/FOXEERF722V4/target.c b/src/main/target/FOXEERF722V4/target.c
new file mode 100644
index 0000000000..f0ad3a1f43
--- /dev/null
+++ b/src/main/target/FOXEERF722V4/target.c
@@ -0,0 +1,45 @@
+/*
+ * 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
+
+#include "platform.h"
+#include "drivers/io.h"
+
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM&SBUS
+
+ DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR, 0, 0), // S1
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0), // S2
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // S3
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // S4
+ DEF_TIM(TIM8, CH1, PC6, TIM_USE_ANY, 0, 0), // TX6
+ DEF_TIM(TIM8, CH2, PC7, TIM_USE_ANY, 0, 0), // RX6
+
+
+ DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED STRIP(1,5)
+
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // FC CAM
+
+};
diff --git a/src/main/target/FOXEERF722V4/target.h b/src/main/target/FOXEERF722V4/target.h
new file mode 100644
index 0000000000..1ceef9ed9e
--- /dev/null
+++ b/src/main/target/FOXEERF722V4/target.h
@@ -0,0 +1,154 @@
+/*
+ * 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 "FXF7"
+#define USBD_PRODUCT_STRING "FOXEERF722V4"
+
+#define USE_GYRO
+#define USE_ACC
+#define USE_EXTI
+//#define USE_GYRO_SPI_MPU6000
+//#define USE_ACC_SPI_MPU6000
+#define USE_GYRO_SPI_ICM42688P
+#define USE_ACC_SPI_ICM42688P
+
+#define MPU_INT_EXTI PC4
+#define MPU6000_CS_PIN PB2
+#define ICM42688P_CS_PIN PB2
+#define MPU6000_SPI_INSTANCE SPI1
+#define ICM42688P_SPI_INSTANCE SPI1
+#define GYRO_MPU6000_ALIGN CW270_DEG
+#define GYRO_ICM42688P_ALIGN CW270_DEG
+#define ACC_MPU6000_ALIGN CW270_DEG
+#define ACC_ICM42688P_ALIGN CW270_DEG
+
+#define USE_MPU_DATA_READY_SIGNAL
+#define ENSURE_MPU_DATA_READY_IS_LOW
+
+#define ENABLE_DSHOT_DMAR true
+#define LED0_PIN PC15
+
+#define USE_BEEPER
+#define BEEPER_PIN PA4
+#define BEEPER_INVERTED
+
+#define CAMERA_CONTROL_PIN PB3
+
+#define USE_BARO
+#define USE_BARO_MS5611
+#define USE_BARO_BMP280
+#define BARO_I2C_INSTANCE (I2CDEV_1)
+
+#define USE_MAG
+#define USE_MAG_HMC5883
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+
+
+#define USE_VCP
+#define USE_UART1
+#define USE_UART2
+#define USE_UART3
+#define USE_UART4
+#define USE_UART5
+#define USE_UART6
+
+#define UART1_TX_PIN PB6
+#define UART1_RX_PIN PB7
+
+#define UART2_TX_PIN PA2
+#define UART2_RX_PIN PA3
+
+#define UART3_TX_PIN PB10
+#define UART3_RX_PIN PB11
+
+#define UART4_TX_PIN PA0
+#define UART4_RX_PIN PA1
+
+#define UART5_TX_PIN PC12
+#define UART5_RX_PIN PD2
+
+#define UART6_TX_PIN PC6
+#define UART6_RX_PIN PC7
+
+#define SERIAL_PORT_COUNT 7
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE I2CDEV_1
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+
+#define USE_SPI
+
+#define USE_SPI_DEVICE_1 // 2xGYRO/ACC
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+
+#define USE_SPI_DEVICE_2 // FLASH
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+
+#define USE_MAX7456
+#define MAX7456_SPI_INSTANCE SPI3
+#define MAX7456_SPI_CS_PIN PC3
+
+#define USE_SPI_DEVICE_3 // MAX7456
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PB5
+
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+#define USE_FLASHFS
+#define USE_FLASH_W25M512
+#define USE_FLASH_M25P16
+#define FLASH_CS_PIN PB12
+#define FLASH_SPI_INSTANCE SPI2
+
+#define USE_ADC
+#define ADC_INSTANCE ADC3
+#define ADC3_DMA_STREAM DMA2_Stream0
+
+#define VBAT_ADC_PIN PC0
+#define CURRENT_METER_ADC_PIN PC2
+#define RSSI_ADC_PIN PA0
+
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+
+#define USE_OSD
+#define USE_LED_STRIP
+
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+#define DEFAULT_FEATURES FEATURE_OSD
+#define SERIALRX_UART SERIAL_PORT_USART1
+#define SERIALRX_PROVIDER SERIALRX_SBUS
+
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+
+#define USABLE_TIMER_CHANNEL_COUNT 9
+#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(4) |TIM_N(8) )
diff --git a/src/main/target/FOXEERF722V4/target.mk b/src/main/target/FOXEERF722V4/target.mk
new file mode 100644
index 0000000000..732e2e0d3e
--- /dev/null
+++ b/src/main/target/FOXEERF722V4/target.mk
@@ -0,0 +1,14 @@
+F7X2RE_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+ drivers/barometer/barometer_bmp280.c \
+ drivers/barometer/barometer_ms5611.c \
+ drivers/compass/compass_hmc5883l.c \
+ drivers/max7456.c \
+ drivers/accgyro/accgyro_mpu6500.c \
+ drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c
+
+
diff --git a/src/main/target/FOXEERF745V3_AIO/target.c b/src/main/target/FOXEERF745V3_AIO/target.c
new file mode 100644
index 0000000000..bbdaad53be
--- /dev/null
+++ b/src/main/target/FOXEERF745V3_AIO/target.c
@@ -0,0 +1,40 @@
+/*
+ * 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
+
+#include "platform.h"
+#include "drivers/io.h"
+
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+
+DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0 ), // LED_STRIP,
+DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // CAMCONTR,
+
+DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0 ), // M1
+DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0 ), // M2
+DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0 ), // M3
+DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0 ), // M4
+
+ };
diff --git a/src/main/target/FOXEERF745V3_AIO/target.h b/src/main/target/FOXEERF745V3_AIO/target.h
new file mode 100644
index 0000000000..17acdf78a4
--- /dev/null
+++ b/src/main/target/FOXEERF745V3_AIO/target.h
@@ -0,0 +1,161 @@
+/*
+ * 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 "FOXE"
+ #define USBD_PRODUCT_STRING "FOXEERF745V3_AIO"
+
+ #define LED0_PIN PC13
+
+ #define USE_BEEPER
+ #define BEEPER_PIN PD2
+ #define BEEPER_INVERTED
+
+ #define CAMERA_CONTROL_PIN PB3
+
+ #define ICM42688P_CS_PIN PA15
+ #define ICM42688P_SPI_INSTANCE SPI3
+
+ #define USE_ACC
+ #define USE_ACC_SPI_ICM42688P
+ #define ACC_ICM42688P_ALIGN CW180_DEG
+
+ #define USE_GYRO
+ #define USE_GYRO_SPI_ICM42688P
+ #define GYRO_ICM42688P_ALIGN CW180_DEG
+
+ // MPU6000 interrupts
+ #define USE_MPU_DATA_READY_SIGNAL
+ #define MPU_INT_EXTI PD0
+ #define USE_EXTI
+
+ #define USE_MAG
+ #define USE_MAG_HMC5883
+ #define USE_MAG_QMC5883
+ #define USE_MAG_LIS3MDL
+ #define MAG_I2C_INSTANCE (I2CDEV_1)
+ //#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
+ //#define MAG_ALIGN CW180_DEG //not sure if this command will work or if should be more specific to mag
+
+ #define USE_BARO
+ #define USE_BARO_BMP280
+ #define BARO_I2C_INSTANCE (I2CDEV_1)
+
+ #define USE_VCP
+ #define USE_USB_DETECT
+ //#define USB_DETECT_PIN PA8
+
+ #define USE_UART1
+ #define UART1_RX_PIN PA10
+ #define UART1_TX_PIN PA9
+
+ #define USE_UART2
+ #define UART2_RX_PIN PA3
+ #define UART2_TX_PIN PA2
+
+ #define USE_UART3
+ #define UART3_RX_PIN PB11
+ #define UART3_TX_PIN PB10
+
+ #define USE_UART4
+ #define UART4_RX_PIN PA1
+ #define UART4_TX_PIN PA0
+
+ #define USE_UART7
+ #define UART7_RX_PIN PE7
+ #define UART7_TX_PIN PE8
+
+ #define SERIAL_PORT_COUNT 6 //VCP, USART1, USART2, USART3, UART4, USART7
+
+ #define USE_ESC_SENSOR
+
+ #define USE_SPI
+ #define USE_SPI_DEVICE_1 //osd
+ #define USE_SPI_DEVICE_2 //?
+ #define USE_SPI_DEVICE_3 //gyro
+ #define USE_SPI_DEVICE_4 //flash
+
+
+ #define SPI1_SCK_PIN PA5
+ #define SPI1_MISO_PIN PA6
+ #define SPI1_MOSI_PIN PA7
+
+
+ #define SPI2_SCK_PIN PB13
+ #define SPI2_MISO_PIN PB14
+ #define SPI2_MOSI_PIN PB15
+
+ #define SPI3_SCK_PIN PC10
+ #define SPI3_MISO_PIN PC11
+ #define SPI3_MOSI_PIN PC12
+
+ #define SPI4_SCK_PIN PE2
+ #define SPI4_MISO_PIN PE5
+ #define SPI4_MOSI_PIN PE6
+
+ #define USE_MAX7456
+ #define MAX7456_SPI_INSTANCE SPI1
+ #define MAX7456_SPI_CS_PIN PA4
+ #define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz
+ #define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
+
+ //#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
+ #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+ #define USE_FLASHFS
+ #define USE_FLASH_M25P16
+ #define FLASH_CS_PIN PE4
+ #define FLASH_SPI_INSTANCE SPI4
+
+ #define USE_I2C
+ #define USE_I2C_DEVICE_1
+ #define I2C_DEVICE_1 (I2CDEV_1)
+ #define I2C1_SCL PB8
+ #define I2C1_SDA PB9
+
+ #define USE_ADC
+ #define VBAT_ADC_PIN PC3
+ #define CURRENT_METER_ADC_PIN PC2
+ #define RSSI_ADC_PIN PC5
+ #define EXTERNAL1_ADC_PIN PC1
+ #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+ #define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+ #define CURRENT_METER_SCALE_DEFAULT 100
+
+ #define USE_LED_STRIP
+ #define LED_STRIP_PIN PA8
+ #define USE_RX_MSP
+// #define RX_MSP_UART SERIAL_PORT_USART5 //default uart5 MSP on
+
+ #define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_OSD)
+ #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+ #define SERIALRX_PROVIDER SERIALRX_SBUS
+ #define SERIALRX_UART SERIAL_PORT_USART1
+ #define USE_DSHOT
+
+ #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 USABLE_TIMER_CHANNEL_COUNT 6
+
+ #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) )
diff --git a/src/main/target/FOXEERF745V3_AIO/target.mk b/src/main/target/FOXEERF745V3_AIO/target.mk
new file mode 100644
index 0000000000..2a684318fe
--- /dev/null
+++ b/src/main/target/FOXEERF745V3_AIO/target.mk
@@ -0,0 +1,12 @@
+F7X5XG_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+ drivers/accgyro/accgyro_spi_icm42688p.c\
+ drivers/accgyro/accgyro_mpu.c \
+ drivers/barometer/barometer_bmp280.c \
+ drivers/compass/compass_hmc5883l.c \
+ drivers/compass/compass_qmc5883l.c \
+ drivers/compass/compass_lis3mdl.c \
+ drivers/light_ws2811strip.c \
+ drivers/max7456.c
From 1acaaf64a01f4394432b1bac7f9a0ea2cfa68132 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Tue, 28 Mar 2023 10:49:48 -0500
Subject: [PATCH 02/22] ICM426xx - very dont know, part deaux
---
src/main/common/utils.h | 2 +
src/main/drivers/accgyro/accgyro.h | 5 +
.../drivers/accgyro/accgyro_spi_icm426xx.c | 235 +++++++++++++++---
src/main/drivers/bus_spi.c | 27 ++
src/main/drivers/bus_spi.h | 5 +
src/main/interface/settings.c | 4 +-
src/main/sensors/acceleration.c | 2 +-
src/main/sensors/gyro.c | 2 +-
src/main/target/FOXEERF722V4/target.mk | 2 -
src/main/target/FOXEERF745V3_AIO/target.mk | 6 +-
10 files changed, 243 insertions(+), 47 deletions(-)
diff --git a/src/main/common/utils.h b/src/main/common/utils.h
index 8cd021d1ff..95f2716244 100644
--- a/src/main/common/utils.h
+++ b/src/main/common/utils.h
@@ -103,6 +103,8 @@ static inline int32_t cmp32(uint32_t a, uint32_t b) {
return (int32_t)(a - b);
}
+static inline uint32_t llog2(uint32_t n) { return 31 - __builtin_clz(n | 1); }
+
// using memcpy_fn will force memcpy function call, instead of inlining it. In most cases function call takes fewer instructions
// than inlined version (inlining is cheaper for very small moves < 8 bytes / 2 store instructions)
#if defined(UNIT_TEST) || defined(SIMULATOR_BUILD)
diff --git a/src/main/drivers/accgyro/accgyro.h b/src/main/drivers/accgyro/accgyro.h
index a29d931c25..7c15965ba6 100644
--- a/src/main/drivers/accgyro/accgyro.h
+++ b/src/main/drivers/accgyro/accgyro.h
@@ -44,6 +44,9 @@
#define GYRO_32KHZ_HARDWARE_LPF_NORMAL 0
#define GYRO_32KHZ_HARDWARE_LPF_EXPERIMENTAL 1
+#define GYRO_HARDWARE_LPF_OPTION_1 1
+#define GYRO_HARDWARE_LPF_OPTION_2 2
+
#define GYRO_LPF_256HZ 0
#define GYRO_LPF_188HZ 1
#define GYRO_LPF_98HZ 2
@@ -91,6 +94,8 @@ typedef struct gyroDev_s {
ioTag_t mpuIntExtiTag;
uint8_t gyroHasOverflowProtection;
gyroSensor_e gyroHardware;
+ uint8_t accDataReg;
+ uint8_t gyroDataReg;
} gyroDev_t;
typedef struct accDev_s {
diff --git a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c
index 6d837775de..b083d85d0b 100644
--- a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c
+++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c
@@ -24,6 +24,8 @@
#include "platform.h"
+#if defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P)
+
#include "common/axis.h"
#include "common/maths.h"
@@ -40,25 +42,40 @@
// 24 MHz max SPI frequency
#define ICM426XX_MAX_SPI_CLK_HZ 24000000
-#define ICM426XX_RA_PWR_MGMT0 0x4E
+#define ICM426XX_RA_REG_BANK_SEL 0x76
+#define ICM426XX_BANK_SELECT0 0x00
+#define ICM426XX_BANK_SELECT1 0x01
+#define ICM426XX_BANK_SELECT2 0x02
+#define ICM426XX_BANK_SELECT3 0x03
+#define ICM426XX_BANK_SELECT4 0x04
+#define ICM426XX_RA_PWR_MGMT0 0x4E // User Bank 0
#define ICM426XX_PWR_MGMT0_ACCEL_MODE_LN (3 << 0)
#define ICM426XX_PWR_MGMT0_GYRO_MODE_LN (3 << 2)
+#define ICM426XX_PWR_MGMT0_GYRO_ACCEL_MODE_OFF ((0 << 0) | (0 << 2))
#define ICM426XX_PWR_MGMT0_TEMP_DISABLE_OFF (0 << 5)
#define ICM426XX_PWR_MGMT0_TEMP_DISABLE_ON (1 << 5)
#define ICM426XX_RA_GYRO_CONFIG0 0x4F
#define ICM426XX_RA_ACCEL_CONFIG0 0x50
-#define ICM426XX_RA_GYRO_ACCEL_CONFIG0 0x52
-
-#define ICM426XX_ACCEL_UI_FILT_BW_LOW_LATENCY (14 << 4)
-#define ICM426XX_GYRO_UI_FILT_BW_LOW_LATENCY (14 << 0)
+// --- Registers for gyro and acc Anti-Alias Filter ---------
+#define ICM426XX_RA_GYRO_CONFIG_STATIC3 0x0C // User Bank 1
+#define ICM426XX_RA_GYRO_CONFIG_STATIC4 0x0D // User Bank 1
+#define ICM426XX_RA_GYRO_CONFIG_STATIC5 0x0E // User Bank 1
+#define ICM426XX_RA_ACCEL_CONFIG_STATIC2 0x03 // User Bank 2
+#define ICM426XX_RA_ACCEL_CONFIG_STATIC3 0x04 // User Bank 2
+#define ICM426XX_RA_ACCEL_CONFIG_STATIC4 0x05 // User Bank 2
+// --- Register & setting for gyro and acc UI Filter --------
+#define ICM426XX_RA_GYRO_ACCEL_CONFIG0 0x52 // User Bank 0
+#define ICM426XX_ACCEL_UI_FILT_BW_LOW_LATENCY (15 << 4)
+#define ICM426XX_GYRO_UI_FILT_BW_LOW_LATENCY (15 << 0)
+// ----------------------------------------------------------
-#define ICM426XX_RA_GYRO_DATA_X1 0x25
-#define ICM426XX_RA_ACCEL_DATA_X1 0x1F
+#define ICM426XX_RA_GYRO_DATA_X1 0x25 // User Bank 0
+#define ICM426XX_RA_ACCEL_DATA_X1 0x1F // User Bank 0
-#define ICM426XX_RA_INT_CONFIG 0x14
+#define ICM426XX_RA_INT_CONFIG 0x14 // User Bank 0
#define ICM426XX_INT1_MODE_PULSED (0 << 2)
#define ICM426XX_INT1_MODE_LATCHED (1 << 2)
#define ICM426XX_INT1_DRIVE_CIRCUIT_OD (0 << 1)
@@ -66,13 +83,13 @@
#define ICM426XX_INT1_POLARITY_ACTIVE_LOW (0 << 0)
#define ICM426XX_INT1_POLARITY_ACTIVE_HIGH (1 << 0)
-#define ICM426XX_RA_INT_CONFIG0 0x63
+#define ICM426XX_RA_INT_CONFIG0 0x63 // User Bank 0
#define ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR ((0 << 5) || (0 << 4))
#define ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR_DUPLICATE ((0 << 5) || (0 << 4)) // duplicate settings in datasheet, Rev 1.2.
#define ICM426XX_UI_DRDY_INT_CLEAR_ON_F1BR ((1 << 5) || (0 << 4))
#define ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR_AND_F1BR ((1 << 5) || (1 << 4))
-#define ICM426XX_RA_INT_CONFIG1 0x64
+#define ICM426XX_RA_INT_CONFIG1 0x64 // User Bank 0
#define ICM426XX_INT_ASYNC_RESET_BIT 4
#define ICM426XX_INT_TDEASSERT_DISABLE_BIT 5
#define ICM426XX_INT_TDEASSERT_ENABLED (0 << ICM426XX_INT_TDEASSERT_DISABLE_BIT)
@@ -81,11 +98,56 @@
#define ICM426XX_INT_TPULSE_DURATION_100 (0 << ICM426XX_INT_TPULSE_DURATION_BIT)
#define ICM426XX_INT_TPULSE_DURATION_8 (1 << ICM426XX_INT_TPULSE_DURATION_BIT)
-
-#define ICM426XX_RA_INT_SOURCE0 0x65
+#define ICM426XX_RA_INT_SOURCE0 0x65 // User Bank 0
#define ICM426XX_UI_DRDY_INT1_EN_DISABLED (0 << 3)
#define ICM426XX_UI_DRDY_INT1_EN_ENABLED (1 << 3)
+typedef enum {
+ ODR_CONFIG_8K = 0,
+ ODR_CONFIG_4K,
+ ODR_CONFIG_2K,
+ ODR_CONFIG_1K,
+ ODR_CONFIG_COUNT
+} odrConfig_e;
+
+typedef enum {
+ AAF_CONFIG_258HZ = 0,
+ AAF_CONFIG_536HZ,
+ AAF_CONFIG_997HZ,
+ AAF_CONFIG_1962HZ,
+ AAF_CONFIG_COUNT
+} aafConfig_e;
+
+typedef struct aafConfig_s {
+ uint8_t delt;
+ uint16_t deltSqr;
+ uint8_t bitshift;
+} aafConfig_t;
+
+// Possible output data rates (ODRs)
+static uint8_t odrLUT[ODR_CONFIG_COUNT] = { // see GYRO_ODR in section 5.6
+ [ODR_CONFIG_8K] = 3,
+ [ODR_CONFIG_4K] = 4,
+ [ODR_CONFIG_2K] = 5,
+ [ODR_CONFIG_1K] = 6,
+};
+
+// Possible gyro Anti-Alias Filter (AAF) cutoffs for ICM-42688P
+static aafConfig_t aafLUT42688[AAF_CONFIG_COUNT] = { // see table in section 5.3
+ [AAF_CONFIG_258HZ] = { 6, 36, 10 },
+ [AAF_CONFIG_536HZ] = { 12, 144, 8 },
+ [AAF_CONFIG_997HZ] = { 21, 440, 6 },
+ [AAF_CONFIG_1962HZ] = { 37, 1376, 4 },
+};
+
+// Possible gyro Anti-Alias Filter (AAF) cutoffs for ICM-42688P
+// actual cutoff differs slightly from those of the 42688P
+static aafConfig_t aafLUT42605[AAF_CONFIG_COUNT] = { // see table in section 5.3
+ [AAF_CONFIG_258HZ] = { 21, 440, 6 }, // actually 249 Hz
+ [AAF_CONFIG_536HZ] = { 39, 1536, 4 }, // actually 524 Hz
+ [AAF_CONFIG_997HZ] = { 63, 3968, 3 }, // actually 995 Hz
+ [AAF_CONFIG_1962HZ] = { 63, 3968, 3 }, // 995 Hz is the max cutoff on the 42605
+};
static void icm426xxSpiInit(const busDevice_t *bus) {
static bool hardwareInitialised = false;
@@ -149,35 +211,94 @@ bool icm426xxSpiAccDetect(accDev_t *acc) {
return true;
}
-void icm426xxGyroInit(gyroDev_t *gyro) {
+static aafConfig_t getGyroAafConfig(const mpuSensor_e, const aafConfig_e);
+
+static void turnGyroAccOff(const gyroDev_t *gyro)
+{
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_PWR_MGMT0, ICM426XX_PWR_MGMT0_GYRO_ACCEL_MODE_OFF);
+}
+
+// Turn on gyro and acc on in Low Noise mode
+static void turnGyroAccOn(const gyroDev_t *gyro)
+{
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_PWR_MGMT0, ICM426XX_PWR_MGMT0_TEMP_DISABLE_OFF | ICM426XX_PWR_MGMT0_ACCEL_MODE_LN | ICM426XX_PWR_MGMT0_GYRO_MODE_LN);
+ delay(1);
+}
+
+static void setUserBank(const gyroDev_t *gyro, const uint8_t user_bank)
+{
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_REG_BANK_SEL, user_bank & 7);
+}
+
+void icm426xxGyroInit(gyroDev_t *gyro)
+{
mpuGyroInit(gyro);
- spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATION);
- spiBusWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, ICM426xx_BIT_RESET);
- delay(100);
- spiBusWriteRegister(&gyro->bus, MPU_RA_SIGNAL_PATH_RESET, 0x03);
- delay(100);
-// spiBusWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, 0);
-// delay(100);
- spiBusWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, INV_CLK_PLL);
- delay(15);
- spiBusWriteRegister(&gyro->bus, MPU_RA_GYRO_CONFIG, (3 - INV_FSR_2000DPS) << 5 | mpuGyroFCHOICE(gyro));
- delay(15);
- spiBusWriteRegister(&gyro->bus, MPU_RA_ACCEL_CONFIG, (3 - INV_FSR_16G) << 5);
- delay(15);
- spiBusWriteRegister(&gyro->bus, MPU_RA_CONFIG, mpuGyroDLPF(gyro));
+
+ spiSetDivisor(gyro->bus.busdev_u.spi.instance, spiCalculateDivider(ICM426XX_MAX_SPI_CLK_HZ));
+
+ gyro->accDataReg = ICM426XX_RA_ACCEL_DATA_X1;
+ gyro->gyroDataReg = ICM426XX_RA_GYRO_DATA_X1;
+
+ // Turn off ACC and GYRO so they can be configured
+ // See section 12.9 in ICM-42688-P datasheet v1.7
+ setUserBank(gyro, ICM426XX_BANK_SELECT0);
+ turnGyroAccOff(gyro);
+
+ // Configure gyro Anti-Alias Filter (see section 5.3 "ANTI-ALIAS FILTER")
+ const mpuSensor_e gyroModel = gyro->mpuDetectionResult.sensor;
+ aafConfig_t aafConfig = getGyroAafConfig(gyroModel, gyroConfig()->gyro_hardware_lpf);
+ setUserBank(gyro, ICM426XX_BANK_SELECT1);
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_GYRO_CONFIG_STATIC3, aafConfig.delt);
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_GYRO_CONFIG_STATIC4, aafConfig.deltSqr & 0xFF);
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_GYRO_CONFIG_STATIC5, (aafConfig.deltSqr >> 8) | (aafConfig.bitshift << 4));
+
+ // Configure acc Anti-Alias Filter for 1kHz sample rate (see tasks.c)
+ aafConfig = getGyroAafConfig(gyroModel, AAF_CONFIG_258HZ);
+ setUserBank(gyro, ICM426XX_BANK_SELECT2);
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_ACCEL_CONFIG_STATIC2, aafConfig.delt << 1);
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_ACCEL_CONFIG_STATIC3, aafConfig.deltSqr & 0xFF);
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_ACCEL_CONFIG_STATIC4, (aafConfig.deltSqr >> 8) | (aafConfig.bitshift << 4));
+
+ // Configure gyro and acc UI Filters
+ setUserBank(gyro, ICM426XX_BANK_SELECT0);
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_GYRO_ACCEL_CONFIG0, ICM426XX_ACCEL_UI_FILT_BW_LOW_LATENCY | ICM426XX_GYRO_UI_FILT_BW_LOW_LATENCY);
+
+ // Configure interrupt pin
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_INT_CONFIG, ICM426XX_INT1_MODE_PULSED | ICM426XX_INT1_DRIVE_CIRCUIT_PP | ICM426XX_INT1_POLARITY_ACTIVE_HIGH);
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_INT_CONFIG0, ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR);
+
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_INT_SOURCE0, ICM426XX_UI_DRDY_INT1_EN_ENABLED);
+
+ uint8_t intConfig1Value = spiReadRegMsk(&gyro->bus, ICM426XX_RA_INT_CONFIG1);
+ // Datasheet says: "User should change setting to 0 from default setting of 1, for proper INT1 and INT2 pin operation"
+ intConfig1Value &= ~(1 << ICM426XX_INT_ASYNC_RESET_BIT);
+ intConfig1Value |= (ICM426XX_INT_TPULSE_DURATION_8 | ICM426XX_INT_TDEASSERT_DISABLED);
+
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_INT_CONFIG1, intConfig1Value);
+
+ // Turn on gyro and acc on again so ODR and FSR can be configured
+ turnGyroAccOn(gyro);
+
+ // Get desired output data rate
+ uint8_t odrConfig;
+ const unsigned decim = llog2(gyro->mpuDividerDrops + 1);
+ if (gyro->gyroRateKHz && decim < ODR_CONFIG_COUNT) {
+ odrConfig = odrLUT[decim];
+ } else {
+ odrConfig = odrLUT[ODR_CONFIG_1K];
+ gyro->gyroRateKHz = GYRO_RATE_1_kHz;
+ }
+
+ STATIC_ASSERT(INV_FSR_2000DPS == 3, INV_FSR_2000DPS_must_be_3_to_generate_correct_value);
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_GYRO_CONFIG0, (3 - INV_FSR_2000DPS) << 5 | (odrConfig & 0x0F));
delay(15);
- spiBusWriteRegister(&gyro->bus, MPU_RA_SMPLRT_DIV, gyro->mpuDividerDrops); // Get Divider Drops
- delay(100);
- // Data ready interrupt configuration
-// spiBusWriteRegister(&gyro->bus, MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 0 << 1 | 0 << 0); // INT_ANYRD_2CLEAR, BYPASS_EN
- spiBusWriteRegister(&gyro->bus, MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR, BYPASS_EN
+
+ STATIC_ASSERT(INV_FSR_16G == 3, INV_FSR_16G_must_be_3_to_generate_correct_value);
+ spiBusWriteRegister(&gyro->bus, ICM426XX_RA_ACCEL_CONFIG0, (3 - INV_FSR_16G) << 5 | (odrConfig & 0x0F));
delay(15);
-#ifdef USE_MPU_DATA_READY_SIGNAL
- spiBusWriteRegister(&gyro->bus, MPU_RA_INT_ENABLE, 0x01); // RAW_RDY_EN interrupt enable
-#endif
- spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_STANDARD);
}
+
bool icm426xxSpiGyroDetect(gyroDev_t *gyro) {
switch (gyro->mpuDetectionResult.sensor) {
case ICM_42605_SPI:
@@ -186,9 +307,47 @@ bool icm426xxSpiGyroDetect(gyroDev_t *gyro) {
default:
return false;
}
+
gyro->initFn = icm426xxGyroInit;
gyro->readFn = mpuGyroReadSPI;
- // 16.4 dps/lsb scalefactor
- gyro->scale = 1.0f / 16.4f;
+
+ gyro->scale = (2000.0f / (1 << 15)); // 16.384 dps/lsb scalefactor for 2000dps sensors
+
return true;
}
+
+static aafConfig_t getGyroAafConfig(const mpuSensor_e gyroModel, const aafConfig_e config)
+{
+ switch (gyroModel){
+ case ICM_42605_SPI:
+ switch (config) {
+ case GYRO_HARDWARE_LPF_NORMAL:
+ return aafLUT42605[AAF_CONFIG_258HZ];
+ case GYRO_HARDWARE_LPF_OPTION_1:
+ return aafLUT42605[AAF_CONFIG_536HZ];
+ case GYRO_HARDWARE_LPF_OPTION_2:
+ return aafLUT42605[AAF_CONFIG_997HZ];
+ default:
+ return aafLUT42605[AAF_CONFIG_258HZ];
+ }
+
+ case ICM_42688P_SPI:
+ default:
+ switch (config) {
+ case GYRO_HARDWARE_LPF_NORMAL:
+ return aafLUT42688[AAF_CONFIG_258HZ];
+ case GYRO_HARDWARE_LPF_OPTION_1:
+ return aafLUT42688[AAF_CONFIG_536HZ];
+ case GYRO_HARDWARE_LPF_OPTION_2:
+ return aafLUT42688[AAF_CONFIG_997HZ];
+#ifdef USE_GYRO_DLPF_EXPERIMENTAL
+ case GYRO_HARDWARE_LPF_EXPERIMENTAL:
+ return aafLUT42688[AAF_CONFIG_1962HZ];
+#endif
+ default:
+ return aafLUT42688[AAF_CONFIG_258HZ];
+ }
+ }
+}
+
+#endif // USE_GYRO_SPI_ICM42605 || USE_GYRO_SPI_ICM42688P
diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c
index 93cec8510a..d0da693b6e 100644
--- a/src/main/drivers/bus_spi.c
+++ b/src/main/drivers/bus_spi.c
@@ -252,3 +252,30 @@ void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance) {
bus->busdev_u.spi.instance = instance;
}
#endif
+
+
+uint16_t spiCalculateDivider(uint32_t freq)
+{
+#if defined(STM32F4) || defined(STM32G4) || defined(STM32F7)
+ uint32_t spiClk = SystemCoreClock / 2;
+#elif defined(STM32H7)
+ uint32_t spiClk = 100000000;
+#elif defined(AT32F4)
+ if(freq > 36000000){
+ freq = 36000000;
+ }
+ uint32_t spiClk = system_core_clock / 2;
+#else
+#error "Base SPI clock not defined for this architecture"
+#endif
+ uint16_t divisor = 2;
+ spiClk >>= 1;
+ for (; (spiClk > freq) && (divisor < 256); divisor <<= 1, spiClk >>= 1);
+ return divisor;
+}
+
+// Wait for bus to become free, then read a byte of data where the register is ORed with 0x80
+uint8_t spiReadRegMsk(const busDevice_t *bus, uint8_t reg)
+{
+ return spiBusReadRegister(bus, reg | 0x80);
+}
diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h
index 12d8d068a7..1fa4a0dab7 100644
--- a/src/main/drivers/bus_spi.h
+++ b/src/main/drivers/bus_spi.h
@@ -121,3 +121,8 @@ void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance);
struct spiPinConfig_s;
void spiPinConfigure(const struct spiPinConfig_s *pConfig);
+
+// Determine the divisor to use for a given bus frequency
+uint16_t spiCalculateDivider(uint32_t freq);
+
+uint8_t spiReadRegMsk(const busDevice_t *bus, uint8_t reg);
diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c
index 0b6664170c..42db3695c7 100644
--- a/src/main/interface/settings.c
+++ b/src/main/interface/settings.c
@@ -109,13 +109,13 @@
const char * const lookupTableAccHardware[] = {
"AUTO", "NONE", "ADXL345", "MPU6050", "MMA8452", "BMA280", "LSM303DLHC",
"MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20649", "ICM20689",
- "BMI160", "ACC_IMUF9001", "FAKE"
+ "ICM42605", "ICM42688P", "BMI160", "ACC_IMUF9001", "FAKE"
};
// sync with gyroSensor_e
const char * const lookupTableGyroHardware[] = {
"AUTO", "NONE", "MPU6050", "L3G4200D", "MPU3050", "L3GD20",
"MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20649", "ICM20689",
- "BMI160", "GYRO_IMUF9001", "FAKE"
+ "ICM42605", "ICM42688P", "BMI160", "GYRO_IMUF9001", "FAKE"
};
#if defined(USE_SENSOR_NAMES) || defined(USE_BARO)
diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c
index 86873b177a..62460a182c 100644
--- a/src/main/sensors/acceleration.c
+++ b/src/main/sensors/acceleration.c
@@ -45,10 +45,10 @@
#include "drivers/accgyro/accgyro_spi_bmi160.h"
#include "drivers/accgyro/accgyro_spi_icm20649.h"
#include "drivers/accgyro/accgyro_spi_icm20689.h"
+#include "drivers/accgyro/accgyro_spi_icm426xx.h"
#include "drivers/accgyro/accgyro_spi_mpu6000.h"
#include "drivers/accgyro/accgyro_spi_mpu6500.h"
#include "drivers/accgyro/accgyro_spi_mpu9250.h"
-#include "drivers/accgyro/accgyro_spi_icm426xx.h"
#ifdef USE_ACC_ADXL345
#include "drivers/accgyro_legacy/accgyro_adxl345.h"
diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c
index ba0466bd33..ea1fd635ba 100644
--- a/src/main/sensors/gyro.c
+++ b/src/main/sensors/gyro.c
@@ -46,10 +46,10 @@
#include "drivers/accgyro/accgyro_spi_bmi160.h"
#include "drivers/accgyro/accgyro_spi_icm20649.h"
#include "drivers/accgyro/accgyro_spi_icm20689.h"
+#include "drivers/accgyro/accgyro_spi_icm426xx.h"
#include "drivers/accgyro/accgyro_spi_mpu6000.h"
#include "drivers/accgyro/accgyro_spi_mpu6500.h"
#include "drivers/accgyro/accgyro_spi_mpu9250.h"
-#include "drivers/accgyro/accgyro_spi_icm426xx.h"
#ifdef USE_GYRO_L3G4200D
#include "drivers/accgyro_legacy/accgyro_l3g4200d.h"
diff --git a/src/main/target/FOXEERF722V4/target.mk b/src/main/target/FOXEERF722V4/target.mk
index 732e2e0d3e..3a267c15ed 100644
--- a/src/main/target/FOXEERF722V4/target.mk
+++ b/src/main/target/FOXEERF722V4/target.mk
@@ -10,5 +10,3 @@ TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/accgyro/accgyro_spi_icm426xx.c
-
-
diff --git a/src/main/target/FOXEERF745V3_AIO/target.mk b/src/main/target/FOXEERF745V3_AIO/target.mk
index 2a684318fe..a575053156 100644
--- a/src/main/target/FOXEERF745V3_AIO/target.mk
+++ b/src/main/target/FOXEERF745V3_AIO/target.mk
@@ -2,11 +2,11 @@ F7X5XG_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
- drivers/accgyro/accgyro_spi_icm42688p.c\
- drivers/accgyro/accgyro_mpu.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
+ drivers/accgyro/accgyro_mpu.c \
drivers/barometer/barometer_bmp280.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
- drivers/compass/compass_lis3mdl.c \
+ drivers/compass/compass_lis3mdl.c \
drivers/light_ws2811strip.c \
drivers/max7456.c
From 8996ba1f10d8dc83ebd163ffb716fa7c6e59179d Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Tue, 28 Mar 2023 11:08:09 -0500
Subject: [PATCH 03/22] ICM426xx - very dont know, RUSHBLADEF7HD
---
src/main/target/RUSH_BLADE_F7_HD/target.h | 6 ++++++
src/main/target/RUSH_BLADE_F7_HD/target.mk | 1 +
2 files changed, 7 insertions(+)
diff --git a/src/main/target/RUSH_BLADE_F7_HD/target.h b/src/main/target/RUSH_BLADE_F7_HD/target.h
index 1ad1a5f0c1..66db6bd6ae 100644
--- a/src/main/target/RUSH_BLADE_F7_HD/target.h
+++ b/src/main/target/RUSH_BLADE_F7_HD/target.h
@@ -47,16 +47,22 @@
#define MPU_INT_EXTI PA4
#define MPU6000_CS_PIN PC4
+ #define ICM42688P_CS_PIN PC4
#define MPU6000_SPI_INSTANCE SPI1
+ #define ICM42688P_SPI_INSTANCE SPI1
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
+ #define USE_GYRO_SPI_ICM42688P
#define USE_ACC
#define USE_ACC_SPI_MPU6000
+ #define USE_ACC_SPI_ICM42688P
#define GYRO_MPU6000_ALIGN CW270_DEG
+ #define GYRO_ICM42688P_ALIGN CW270_DEG
#define ACC_MPU6000_ALIGN CW270_DEG
+ #define ACC_ICM42688P_ALIGN CW270_DEG
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
diff --git a/src/main/target/RUSH_BLADE_F7_HD/target.mk b/src/main/target/RUSH_BLADE_F7_HD/target.mk
index 3b2730cf37..521e974eda 100644
--- a/src/main/target/RUSH_BLADE_F7_HD/target.mk
+++ b/src/main/target/RUSH_BLADE_F7_HD/target.mk
@@ -4,6 +4,7 @@ FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
drivers/barometer/barometer_ms5611.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_bmp085.c \
From 1247359dcf593831b105d7c76f39ef4b45bc0963 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Mon, 3 Apr 2023 11:12:34 -0500
Subject: [PATCH 04/22] ICM426xx - same; add accgyro_mpu.c; add icm 42688p to
BETAFPVF722
---
src/main/target/BETAFPVF722/target.h | 10 ++++++++++
src/main/target/BETAFPVF722/target.mk | 1 +
src/main/target/FOXEERF722V4/target.mk | 1 +
3 files changed, 12 insertions(+)
diff --git a/src/main/target/BETAFPVF722/target.h b/src/main/target/BETAFPVF722/target.h
index 31821bc7b2..a3afa80eb3 100644
--- a/src/main/target/BETAFPVF722/target.h
+++ b/src/main/target/BETAFPVF722/target.h
@@ -49,6 +49,16 @@
#define GYRO_MPU6000_ALIGN CW180_DEG
#define ACC_MPU6000_ALIGN CW180_DEG
+
+// ICM42688P
+#define USE_GYRO_SPI_ICM42688P
+#define USE_ACC_SPI_ICM42688P
+#define ICM42688P_CS_PIN PA4
+#define ICM42688P_SPI_INSTANCE SPI1
+#define GYRO_ICM42688P_ALIGN CW180_DEG
+#define ACC_ICM42688P_ALIGN CW180_DEG
+
+
// OSD
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI3
diff --git a/src/main/target/BETAFPVF722/target.mk b/src/main/target/BETAFPVF722/target.mk
index 56beeaedad..0da79a44b5 100644
--- a/src/main/target/BETAFPVF722/target.mk
+++ b/src/main/target/BETAFPVF722/target.mk
@@ -4,6 +4,7 @@ FEATURES = VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_mpu.c \
+drivers/accgyro/accgyro_spi_icm426xx.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
diff --git a/src/main/target/FOXEERF722V4/target.mk b/src/main/target/FOXEERF722V4/target.mk
index 3a267c15ed..3f80ab3aa5 100644
--- a/src/main/target/FOXEERF722V4/target.mk
+++ b/src/main/target/FOXEERF722V4/target.mk
@@ -9,4 +9,5 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_icm426xx.c
From 3ee661e88d43d67602a68527b56e7a57c6c26c73 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Wed, 3 May 2023 16:00:32 -0500
Subject: [PATCH 05/22] ICM426xx - still finding missing elements
---
src/main/drivers/accgyro/accgyro_mpu.c | 13 +++++++++++++
src/main/drivers/accgyro/accgyro_mpu.h | 2 +-
src/main/flight/pid.c | 2 +-
src/main/sensors/gyro.c | 4 ++--
4 files changed, 17 insertions(+), 4 deletions(-)
diff --git a/src/main/drivers/accgyro/accgyro_mpu.c b/src/main/drivers/accgyro/accgyro_mpu.c
index 7f9e96c772..5265e27342 100644
--- a/src/main/drivers/accgyro/accgyro_mpu.c
+++ b/src/main/drivers/accgyro/accgyro_mpu.c
@@ -366,6 +366,19 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro) {
return true;
}
#endif
+#ifdef USE_GYRO_SPI_ICM42605
+#ifdef ICM42605_SPI_INSTANCE
+ spiBusSetInstance(&gyro->bus, ICM42605_SPI_INSTANCE);
+#endif
+#ifdef ICM42605_CS_PIN
+ gyro->bus.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(ICM42605_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin;
+#endif
+ sensor = icm426xxSpiDetect(&gyro->bus);
+ if (sensor != MPU_NONE) {
+ gyro->mpuDetectionResult.sensor = sensor;
+ return true;
+ }
+#endif
#ifdef USE_GYRO_SPI_ICM42688P
#ifdef ICM42688P_SPI_INSTANCE
spiBusSetInstance(&gyro->bus, ICM42688P_SPI_INSTANCE);
diff --git a/src/main/drivers/accgyro/accgyro_mpu.h b/src/main/drivers/accgyro/accgyro_mpu.h
index 6c045ccd44..aa0f770e29 100644
--- a/src/main/drivers/accgyro/accgyro_mpu.h
+++ b/src/main/drivers/accgyro/accgyro_mpu.h
@@ -29,7 +29,7 @@
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#if defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20649) \
- || defined(USE_GYRO_SPI_ICM20689)
+ || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P)
#define GYRO_USES_SPI
#endif
diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c
index bb6f1fbdbb..2344beb3d5 100644
--- a/src/main/flight/pid.c
+++ b/src/main/flight/pid.c
@@ -86,7 +86,7 @@ PG_REGISTER_WITH_RESET_TEMPLATE(pidConfig_t, pidConfig, PG_PID_CONFIG, 2);
#ifdef STM32F10X
#define PID_PROCESS_DENOM_DEFAULT 1
-#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20689)
+#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P)
#define PID_PROCESS_DENOM_DEFAULT 1
#else
#define PID_PROCESS_DENOM_DEFAULT 2
diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c
index ea1fd635ba..b77528e9fd 100644
--- a/src/main/sensors/gyro.c
+++ b/src/main/sensors/gyro.c
@@ -209,7 +209,7 @@ static void gyroInitLowpassFilterLpf(gyroSensor_t *gyroSensor, int slot, int typ
#ifdef STM32F10X
#define GYRO_SYNC_DENOM_DEFAULT 8
#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) \
- || defined(USE_GYRO_SPI_ICM20689)
+ || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P)
#define GYRO_SYNC_DENOM_DEFAULT 1
#else
#define GYRO_SYNC_DENOM_DEFAULT 3
@@ -562,7 +562,7 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev) {
static bool gyroInitSensor(gyroSensor_t *gyroSensor) {
gyroSensor->gyroDev.gyro_high_fsr = gyroConfig()->gyro_high_fsr;
#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) \
- || defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_IMUF9001) || defined(USE_ACCGYRO_BMI160)
+ || defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_GYRO_IMUF9001) || defined(USE_ACCGYRO_BMI160)
mpuDetect(&gyroSensor->gyroDev);
mpuResetFn = gyroSensor->gyroDev.mpuConfiguration.resetFn; // must be set after mpuDetect
#endif
From 11ab40af8c6361f1eb71e51f64ea4002686643c0 Mon Sep 17 00:00:00 2001
From: Peck07 <28628457+Peck07@users.noreply.github.com>
Date: Fri, 19 May 2023 00:34:10 +0200
Subject: [PATCH 06/22] acc/gyro read change for icm426xx
---
.../drivers/accgyro/accgyro_spi_icm426xx.c | 41 ++++++++++++++++++-
1 file changed, 39 insertions(+), 2 deletions(-)
diff --git a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c
index b083d85d0b..eedaf23c27 100644
--- a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c
+++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c
@@ -198,6 +198,22 @@ void icm426xxAccInit(accDev_t *acc) {
acc->acc_1G = 512 * 4;
}
+bool icm426xxAccRead(accDev_t *acc)
+{
+ uint8_t data[6];
+
+ const bool ack = busReadRegisterBuffer(&acc->bus, ICM426XX_RA_ACCEL_DATA_X1, data, 6);
+ if (!ack) {
+ return false;
+ }
+
+ acc->ADCRaw[X] = (int16_t)((data[0] << 8) | data[1]);
+ acc->ADCRaw[Y] = (int16_t)((data[2] << 8) | data[3]);
+ acc->ADCRaw[Z] = (int16_t)((data[4] << 8) | data[5]);
+
+ return true;
+}
+
bool icm426xxSpiAccDetect(accDev_t *acc) {
switch (acc->mpuDetectionResult.sensor) {
case ICM_42605_SPI:
@@ -207,7 +223,7 @@ bool icm426xxSpiAccDetect(accDev_t *acc) {
return false;
}
acc->initFn = icm426xxAccInit;
- acc->readFn = mpuAccRead;
+ acc->readFn = icm426xxAccRead;
return true;
}
@@ -298,6 +314,27 @@ void icm426xxGyroInit(gyroDev_t *gyro)
delay(15);
}
+// MIGHT NOT work on STM32F7
+#define STATIC_DMA_DATA_AUTO static
+//FAST_CODE bool mpuGyroReadSPI(gyroDev_t *gyro)
+bool icm426xxGyroReadSPI(gyroDev_t *gyro)
+{
+ //static const uint8_t dataToSend[7] = {MPU_RA_GYRO_XOUT_H | 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF};
+ STATIC_DMA_DATA_AUTO uint8_t dataToSend[7] = {ICM426XX_RA_GYRO_DATA_X1 | 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF};
+ //uint8_t data[7];
+ STATIC_DMA_DATA_AUTO uint8_t data[7];
+
+ const bool ack = spiBusTransfer(&gyro->bus, dataToSend, data, 7);
+ if (!ack) {
+ return false;
+ }
+
+ gyro->gyroADCRaw[X] = (int16_t)((data[1] << 8) | data[2]);
+ gyro->gyroADCRaw[Y] = (int16_t)((data[3] << 8) | data[4]);
+ gyro->gyroADCRaw[Z] = (int16_t)((data[5] << 8) | data[6]);
+
+ return true;
+}
bool icm426xxSpiGyroDetect(gyroDev_t *gyro) {
switch (gyro->mpuDetectionResult.sensor) {
@@ -309,7 +346,7 @@ bool icm426xxSpiGyroDetect(gyroDev_t *gyro) {
}
gyro->initFn = icm426xxGyroInit;
- gyro->readFn = mpuGyroReadSPI;
+ gyro->readFn = icm426xxGyroReadSPI;
gyro->scale = (2000.0f / (1 << 15)); // 16.384 dps/lsb scalefactor for 2000dps sensors
From 13c2c97fdc6533d1bb98e14d5a60976b192bdf02 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Wed, 24 May 2023 10:49:47 -0500
Subject: [PATCH 07/22] ICM42688P - DIAT_MAMBAF405_2022B; WIP; untested
---
src/main/target/DIAT_MAMBAF405_2022B/target.c | 100 ++++++++++++
src/main/target/DIAT_MAMBAF405_2022B/target.h | 154 ++++++++++++++++++
.../target/DIAT_MAMBAF405_2022B/target.mk | 14 ++
3 files changed, 268 insertions(+)
create mode 100644 src/main/target/DIAT_MAMBAF405_2022B/target.c
create mode 100644 src/main/target/DIAT_MAMBAF405_2022B/target.h
create mode 100644 src/main/target/DIAT_MAMBAF405_2022B/target.mk
diff --git a/src/main/target/DIAT_MAMBAF405_2022B/target.c b/src/main/target/DIAT_MAMBAF405_2022B/target.c
new file mode 100644
index 0000000000..7d472b3254
--- /dev/null
+++ b/src/main/target/DIAT_MAMBAF405_2022B/target.c
@@ -0,0 +1,100 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This 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.
+ *
+ * This software 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 .
+ */
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+/* notice - incomplete */
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP,
+ //DEF_TIM(TIM4, CH3, PB8, TIM_USE_ANY, 0, 0), // baro/mag // no dps310 in EmuFlight,
+ //DEF_TIM(TIM11, CH1, PB9, TIM_USE_ANY, 0, 0), // baro/mag // no dps310 in EmuFlight,
+ DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR, 0, 0 ), // M1
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0 ), // M2
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0 ), // M3
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0 ), // M4
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0 ), // M5
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0 ), // M6
+};
+// notice - this file was programmatically generated and may be incomplete.
+
+// #define MOTOR1_PIN PA9
+// #define MOTOR2_PIN PA8
+// #define MOTOR3_PIN PC9
+// #define MOTOR4_PIN PC8
+// #define MOTOR5_PIN PB0
+// #define MOTOR6_PIN PB1
+
+// #define TIMER_PIN_MAPPING \
+// TIMER_PIN_MAP( 0, PB9 , 2, -1) \
+// TIMER_PIN_MAP( 1, PA9 , 1, 0) \ //m1
+// TIMER_PIN_MAP( 2, PA8 , 1, 0) \ //m2
+// TIMER_PIN_MAP( 3, PC9 , 2, 0) \ //m3
+// TIMER_PIN_MAP( 4, PC8 , 2, 0) \ //m4
+// TIMER_PIN_MAP( 5, PB0 , 2, 0) \ //m5
+// TIMER_PIN_MAP( 6, PB1 , 2, 0) \ //m6
+// TIMER_PIN_MAP( 7, PB8 , 1, 0) \ //I2C1_SCL_PIN //baro/mag?
+// TIMER_PIN_MAP( 8, PB3 , 1, 0) //LED_STRIP_PIN
+
+// # timer
+// timer B09 AF3
+// # pin B09: TIM11 CH1 (AF3) //baro/mag
+// timer A09 AF1
+// # pin A09: TIM1 CH2 (AF1) //m1
+// timer A08 AF1
+// # pin A08: TIM1 CH1 (AF1) //m2
+// timer C09 AF3
+// # pin C09: TIM8 CH4 (AF3) //m3
+// timer C08 AF3
+// # pin C08: TIM8 CH3 (AF3) //m4
+// timer B00 AF2
+// # pin B00: TIM3 CH3 (AF2) //m5
+// timer B01 AF2
+// # pin B01: TIM3 CH4 (AF2) //m6
+// timer B08 AF2
+// # pin B08: TIM4 CH3 (AF2) //baro/mag
+// timer B03 AF1
+// # pin B03: TIM2 CH2 (AF1) //led
+//
+// # dma
+// dma ADC 3 0
+// # ADC 3: DMA2 Stream 0 Channel 2
+// dma pin A09 0
+// # pin A09: DMA2 Stream 6 Channel 0
+// dma pin A08 0
+// # pin A08: DMA2 Stream 6 Channel 0
+// dma pin C09 0
+// # pin C09: DMA2 Stream 7 Channel 7
+// dma pin C08 0
+// # pin C08: DMA2 Stream 2 Channel 0
+// dma pin B00 0
+// # pin B00: DMA1 Stream 7 Channel 5
+// dma pin B01 0
+// # pin B01: DMA1 Stream 2 Channel 5
+// dma pin B08 0
+// # pin B08: DMA1 Stream 7 Channel 2
+// dma pin B03 0
+// # pin B03: DMA1 Stream 6 Channel 3
+
diff --git a/src/main/target/DIAT_MAMBAF405_2022B/target.h b/src/main/target/DIAT_MAMBAF405_2022B/target.h
new file mode 100644
index 0000000000..c96f78e383
--- /dev/null
+++ b/src/main/target/DIAT_MAMBAF405_2022B/target.h
@@ -0,0 +1,154 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This 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.
+ *
+ * This software 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 "DIAT"
+#define USBD_PRODUCT_STRING "MAMBAF405_2022B"
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_ACC_SPI_MPU6500
+#define USE_GYRO_SPI_MPU6500
+#define USE_GYRO_SPI_ICM42688P
+#define USE_ACC_SPI_ICM42688P
+#define USE_BARO_DPS310
+#define USE_FLASH
+#define USE_FLASHFS
+#define USE_FLASH_M25P16
+#define USE_MAX7456
+#define USE_BARO
+#define USE_ADC
+#define USE_SPI_GYRO
+// manual
+#define USE_VCP
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
+
+#define USE_LED
+#define LED0_PIN PC15
+#define LED1_PIN PC14
+#define BEEPER_PIN PC13
+#define BEEPER_INVERTED
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MOSI_PIN PA6
+#define SPI1_MISO_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MOSI_PIN PB14
+#define SPI2_MISO_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PC10
+#define SPI3_MOSI_PIN PC11
+#define SPI3_MISO_PIN PB5
+
+#define USE_EXTI
+
+#define GYRO_1_ALIGN CW270_DEG
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_EXTI_PIN PC4
+#define GYRO_1_SPI_INSTANCE SPI1
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define ACC_MPU6000_ALIGN GYRO_1_ALIGN
+#define GYRO_MPU6000_ALIGN GYRO_1_ALIGN
+#define MPU6000_CS_PIN GYRO_1_CS_PIN
+#define MPU6000_SPI_INSTANCE GYRO_1_SPI_INSTANCE
+#define MPU_INT_EXTI GYRO_1_EXTI_PIN
+
+#define ACC_MPU6500_ALIGN GYRO_1_ALIGN
+#define GYRO_MPU6500_ALIGN GYRO_1_ALIGN
+#define MPU6500_CS_PIN GYRO_1_CS_PIN
+#define MPU6500_SPI_INSTANCE GYRO_1_SPI_INSTANCE
+#define MPU_INT_EXTI GYRO_1_EXTI_PIN
+
+#define ACC_ICM42688P_ALIGN GYRO_1_ALIGN
+#define GYRO_ICM42688P_ALIGN GYRO_1_ALIGN
+#define ICM42688P_CS_PIN GYRO_1_CS_PIN
+#define ICM42688P_SPI_INSTANCE GYRO_1_SPI_INSTANCE
+
+// notice - this file was programmatically generated and may need GYRO_2 manually added.
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+#define BARO_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+
+#define FLASH_CS_PIN PA15
+#define FLASH_SPI_INSTANCE SPI3
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PB12
+#define MAX7456_SPI_INSTANCE SPI2
+
+#define UART1_TX_PIN PB6
+#define UART2_TX_PIN PA2
+#define UART3_TX_PIN PB10
+#define UART4_TX_PIN PA0
+#define UART5_TX_PIN PC12
+#define UART6_TX_PIN PC6
+#define UART1_RX_PIN PB7
+#define UART2_RX_PIN PA3
+#define UART3_RX_PIN PB11
+#define UART4_RX_PIN PA1
+#define UART5_RX_PIN PD2
+#define UART6_RX_PIN PC7
+#define INVERTER_PIN_UART1 PC0
+#define SERIAL_PORT_COUNT 6
+// notice - UART/USART were programmatically generated - must check USART validity.${hFile}
+// notice - may need "#define SERIALRX_UART SERIAL_PORT_USART_"
+// notice - should check serial count.
+
+//manual
+#define USE_UART1
+#define USE_UART2
+#define USE_UART3
+#define USE_UART4
+#define USE_UART5
+#define USE_UART6
+
+
+#define VBAT_ADC_PIN PC1
+#define CURRENT_METER_ADC_PIN PC3
+#define ADC3_DMA_STREAM DMA2_Stream0 // notice - DMA2_Stream0 likely need correcting, please modify.
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 183
+
+#define ENABLE_DSHOT_DMAR true
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - must verify last port group for 0xffff or (BIT(2))
+
+#define USABLE_TIMER_CHANNEL_COUNT 9
+#define USED_TIMERS ( TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4)|TIM_N(8)|TIM_N(11)) /* notice - incomplete */
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/DIAT_MAMBAF405_2022B/target.mk b/src/main/target/DIAT_MAMBAF405_2022B/target.mk
new file mode 100644
index 0000000000..418c2fce24
--- /dev/null
+++ b/src/main/target/DIAT_MAMBAF405_2022B/target.mk
@@ -0,0 +1,14 @@
+F405_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_mpu.c \
+drivers/accgyro/accgyro_mpu6500.c \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/accgyro/accgyro_spi_mpu6500.c \
+drivers/accgyro/accgyro_spi_icm426xx.c \
+drivers/max7456.c
+
+# notice - this file was programmatically generated and may be incomplete.
+# eg: flash, compass, barometer, vtx6705, ledstrip, pinio, etc.
+
From 05c175952c5f2a9b167b03fcf09c88f7a70490c0 Mon Sep 17 00:00:00 2001
From: BeauBrewski <85623381+BeauBrewski@users.noreply.github.com>
Date: Thu, 25 May 2023 10:46:25 -0500
Subject: [PATCH 08/22] Adding ICM4xxxx to GEPRCF722_AIO
---
src/main/target/GEPRC_F722_AIO/target.c | 45 +++++++
src/main/target/GEPRC_F722_AIO/target.h | 158 +++++++++++++++++++++++
src/main/target/GEPRC_F722_AIO/target.mk | 15 +++
3 files changed, 218 insertions(+)
create mode 100644 src/main/target/GEPRC_F722_AIO/target.c
create mode 100644 src/main/target/GEPRC_F722_AIO/target.h
create mode 100644 src/main/target/GEPRC_F722_AIO/target.mk
diff --git a/src/main/target/GEPRC_F722_AIO/target.c b/src/main/target/GEPRC_F722_AIO/target.c
new file mode 100644
index 0000000000..2d5f11353a
--- /dev/null
+++ b/src/main/target/GEPRC_F722_AIO/target.c
@@ -0,0 +1,45 @@
+/*
+ * 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
+
+#include "platform.h"
+#include "drivers/io.h"
+
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), //CAMERA CONTROL
+DEF_TIM(TIM9, CH2, PA3, TIM_USE_ANY, 0, 0), //PPM
+
+DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), //MOTOR 1
+DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 1), //MOTOR 2
+DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 1), //MOTOR 3
+DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0), //MOTOR 4
+
+//DEF_TIM(TIM4, CH1, PB6, TIM_USE_ANY, 0, 0), //in config but match no pins
+//DEF_TIM(TIM4, CH2, PB7, TIM_USE_ANY, 0, 0), //pretty sure left over from
+//DEF_TIM(TIM3, CH4, PB1, TIM_USE_ANY, 0, 0), //geprc_f722_bthd target/config
+//DEF_TIM(TIM3, CH3, PB0, TIM_USE_ANY, 0, 0), //as match motors 5-8
+
+DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0) //LED
+};
diff --git a/src/main/target/GEPRC_F722_AIO/target.h b/src/main/target/GEPRC_F722_AIO/target.h
new file mode 100644
index 0000000000..2cb368bae7
--- /dev/null
+++ b/src/main/target/GEPRC_F722_AIO/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 .
+ *
+ * Prepared by Kaio
+ */
+#pragma once
+
+#define TARGET_BOARD_IDENTIFIER "S7X2"
+#define USBD_PRODUCT_STRING "GEPRC_F722_AIO"
+#define TARGET_MANUFACTURER_IDENTIFIER "GEPR"
+
+#define LED0_PIN PC4
+
+#define USE_BEEPER
+#define BEEPER_PIN PC15
+#define BEEPER_INVERTED
+
+#define ENABLE_DSHOT_DMAR true
+
+#define USE_EXTI
+#define MPU_INT_EXTI PA8
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define USE_GYRO
+
+#define USE_GYRO_SPI_ICM42688P
+#define ICM42688P_CS_PIN PA15
+#define ICM42688P_SPI_INSTANCE SPI1
+#define GYRO_ICM42688P_ALIGN CW90_DEG
+
+#define USE_GYRO_SPI_MPU6000
+#define MPU6000_CS_PIN PA15
+#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_MPU6000_ALIGN CW90_DEG
+
+#define USE_ACC
+
+#define USE_ACC_SPI_ICM42688P
+#define ACC_ICM42688P_ALIGN CW90_DEG
+
+#define USE_ACC_SPI_MPU6000
+#define USE_ACC_SPI_MPU6500
+#define ACC_MPU6000_ALIGN CW90_DEG
+
+#define USE_BARO
+#define USE_BARO_BMP280
+#define USE_BARO_BMP085
+#define USE_BARO_MS5611
+#define BARO_I2C_INSTANCE (I2CDEV_2)
+
+#define USE_MAG
+#define USE_MAG_HMC5883
+#define USE_MAG_QMC5883
+#define MAG_I2C_INSTANCE (I2CDEV_2)
+
+#define USE_MAX7456
+#define MAX7456_SPI_INSTANCE SPI2
+#define MAX7456_SPI_CS_PIN PB12
+
+#define USE_FLASHFS
+#define USE_FLASH_M25P16
+#define FLASH_SPI_INSTANCE SPI3
+#define FLASH_CS_PIN PB9
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define USE_VCP
+#define USE_USB_DETECT
+
+#define USE_UART1
+#define UART1_RX_PIN PA10
+#define UART1_TX_PIN PA9
+
+#define USE_UART2
+#define UART2_RX_PIN PA3
+#define UART2_TX_PIN PA2
+
+#define USE_UART3
+#define UART3_RX_PIN PB11
+#define UART3_TX_PIN PB10
+
+#define USE_UART4
+#define UART4_RX_PIN PC11
+#define UART4_TX_PIN PC10
+
+#define USE_UART5
+#define UART5_RX_PIN PD2
+#define UART5_TX_PIN PC12
+
+#define SERIAL_PORT_COUNT 6 //USB + 5 UARTS
+
+#define USE_ESCSERIAL //PPM
+#define ESCSERIAL_TIMER_TX_PIN PA3
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PB3
+#define SPI3_MISO_PIN PB4
+#define SPI3_MOSI_PIN PB5
+
+//#define USE_I2C
+//#define USE_I2C_DEVICE_1
+//#define I2C1_SCL PB8
+//#define I2C1_SDA PB9
+//#define I2C_DEVICE (I2CDEV_1)
+
+#define USE_I2C_DEVICE_2
+#define I2C2_SCL PB10
+#define I2C2_SDA PB11
+#define I2C_DEVICE (I2CDEV_2)
+
+#define USE_ADC
+#define ADC3_DMA_STREAM DMA2_Stream0
+#define VBAT_ADC_PIN PC2
+#define CURRENT_METER_ADC_PIN PC1
+//#define RSSI_ADC_PIN PC2
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define CURRENT_METER_SCALE_DEFAULT 100
+
+#define SERIALRX_PROVIDER SERIALRX_SBUS
+//#define SERIALRX_UART SERIAL_PORT_USART2
+
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+#define DEFAULT_FEATURES ( FEATURE_OSD | FEATURE_TELEMETRY )
+
+#define TARGET_IO_PORTA ( 0xffff )
+#define TARGET_IO_PORTB ( 0xffff )
+#define TARGET_IO_PORTC ( 0xffff )
+#define TARGET_IO_PORTD ( 0xffff )
+
+#define USABLE_TIMER_CHANNEL_COUNT 7
+#define USED_TIMERS ( TIM_N(2) | TIM_N(5) | TIM_N(8) | TIM_N(9) )
diff --git a/src/main/target/GEPRC_F722_AIO/target.mk b/src/main/target/GEPRC_F722_AIO/target.mk
new file mode 100644
index 0000000000..8047e388fd
--- /dev/null
+++ b/src/main/target/GEPRC_F722_AIO/target.mk
@@ -0,0 +1,15 @@
+F7X2RE_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+TARGET_SRC = \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
+ drivers/accgyro/accgyro_mpu.c \
+ drivers/accgyro/accgyro_mpu6500.c \
+ drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/barometer/barometer_ms5611.c \
+ drivers/barometer/barometer_bmp280.c \
+ drivers/barometer/barometer_bmp085.c \
+ drivers/compass/compass_hmc5883l.c \
+ drivers/compass/compass_qmc5883l.c \
+ drivers/max7456.c\
+ drivers/light_ws2811strip.c
From 80159eda9575c097fa68a7fa8eebed9c66441dad Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Thu, 25 May 2023 11:42:53 -0500
Subject: [PATCH 09/22] ICM42688P - JHEF_JHEF7DUAL; WIP; untested
---
src/main/target/JHEF_JHEF7DUAL/target.c | 117 ++++++++++++++++
src/main/target/JHEF_JHEF7DUAL/target.h | 164 +++++++++++++++++++++++
src/main/target/JHEF_JHEF7DUAL/target.mk | 13 ++
3 files changed, 294 insertions(+)
create mode 100644 src/main/target/JHEF_JHEF7DUAL/target.c
create mode 100644 src/main/target/JHEF_JHEF7DUAL/target.h
create mode 100644 src/main/target/JHEF_JHEF7DUAL/target.mk
diff --git a/src/main/target/JHEF_JHEF7DUAL/target.c b/src/main/target/JHEF_JHEF7DUAL/target.c
new file mode 100644
index 0000000000..82501da5ce
--- /dev/null
+++ b/src/main/target/JHEF_JHEF7DUAL/target.c
@@ -0,0 +1,117 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This 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.
+ *
+ * This software 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 .
+ */
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+/* notice - incomplete */
+// format : DEF_TIM(TIMxx, CHx, Pxx, TIM_USE_xxxxxxx, x, x), //comment
+ DEF_TIM(TIM9, CH2, PA3, TIM_USE_LED, 0, 0), //LED0
+
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // #define MOTOR1_PIN PB0
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // #define MOTOR2_PIN PB1
+ DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // #define MOTOR3_PIN PB4
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR, 0, 0), // #define MOTOR4_PIN PB3
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // #define MOTOR5_PIN PC9
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // #define MOTOR6_PIN PC8
+
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), //LED_STRIP
+ DEF_TIM(TIM4, CH3, PB8, TIM_USE_ANY, 0, 0), //CAM_CONTROL
+
+};
+
+// TIM_USE options:
+// TIM_USE_ANY
+// TIM_USE_BEEPER
+// TIM_USE_LED
+// TIM_USE_MOTOR
+// TIM_USE_NONE
+// TIM_USE_PPM
+// TIM_USE_PWM
+// TIM_USE_SERVO
+// TIM_USE_TRANSPONDER
+
+// config.h resources:
+// #define MOTOR1_PIN PB0
+// #define MOTOR2_PIN PB1
+// #define MOTOR3_PIN PB4
+// #define MOTOR4_PIN PB3
+// #define MOTOR5_PIN PC9
+// #define MOTOR6_PIN PC8
+// #define TIMER_PIN_MAPPING \
+// TIMER_PIN_MAP( 0, PA3 , 3, -1) \
+// TIMER_PIN_MAP( 1, PB0 , 2, 0) \
+// TIMER_PIN_MAP( 2, PB1 , 2, 0) \
+// TIMER_PIN_MAP( 3, PB4 , 1, 0) \
+// TIMER_PIN_MAP( 4, PB3 , 1, 0) \
+// TIMER_PIN_MAP( 5, PC9 , 2, 0) \
+// TIMER_PIN_MAP( 6, PC8 , 2, 0) \
+// TIMER_PIN_MAP( 7, PA8 , 1, 0) \
+// TIMER_PIN_MAP( 8, PB8 , 1, 0)
+
+
+// unified-target:
+// # timer
+// timer A03 AF3
+// # pin A03: TIM9 CH2 (AF3)
+
+// timer B00 AF2
+// # pin B00: TIM3 CH3 (AF2)
+// timer B01 AF2
+// # pin B01: TIM3 CH4 (AF2)
+// timer B04 AF2
+// # pin B04: TIM3 CH1 (AF2)
+// timer B03 AF1
+// # pin B03: TIM2 CH2 (AF1)
+// timer C09 AF3
+// # pin C09: TIM8 CH4 (AF3)
+// timer C08 AF3
+// # pin C08: TIM8 CH3 (AF3)
+
+// timer A08 AF1
+// # pin A08: TIM1 CH1 (AF1)
+// timer B08 AF2
+// # pin B08: TIM4 CH3 (AF2)
+//
+// # dma
+// dma ADC 3 1
+// # ADC 3: DMA2 Stream 1 Channel 2
+// dma pin B00 0
+// # pin B00: DMA1 Stream 7 Channel 5
+// dma pin B01 0
+// # pin B01: DMA1 Stream 2 Channel 5
+// dma pin B04 0
+// # pin B04: DMA1 Stream 4 Channel 5
+// dma pin B03 0
+// # pin B03: DMA1 Stream 6 Channel 3
+// dma pin C09 0
+// # pin C09: DMA2 Stream 7 Channel 7
+// dma pin C08 0
+// # pin C08: DMA2 Stream 2 Channel 0
+// dma pin A08 0
+// # pin A08: DMA2 Stream 6 Channel 0
+// dma pin B08 0
+// # pin B08: DMA1 Stream 7 Channel 2
diff --git a/src/main/target/JHEF_JHEF7DUAL/target.h b/src/main/target/JHEF_JHEF7DUAL/target.h
new file mode 100644
index 0000000000..89c57a5e80
--- /dev/null
+++ b/src/main/target/JHEF_JHEF7DUAL/target.h
@@ -0,0 +1,164 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This 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.
+ *
+ * This software 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 "JHEF"
+#define USBD_PRODUCT_STRING "JHEF7DUAL"
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_ACC_SPI_ICM20689
+#define USE_GYRO_SPI_ICM20689
+#define USE_GYRO_SPI_ICM42688P
+#define USE_ACC_SPI_ICM42688P
+#define USE_BARO_BMP280
+#define USE_FLASH
+#define USE_FLASH_M25P16
+#define USE_MAX7456
+#define USE_BARO
+#define USE_ADC
+#define USE_SPI_GYRO
+
+#define USE_VCP
+#define USE_FLASHFS
+
+#define USE_LED
+#define LED0_PIN PA15
+#define LED_STRIP_PIN PA8
+#define BEEPER_PIN PC15
+#define BEEPER_INVERTED
+#define CAMERA_CONTROL_PIN PB8
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MOSI_PIN PA6
+#define SPI1_MISO_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MOSI_PIN PB14
+#define SPI2_MISO_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PC10
+#define SPI3_MOSI_PIN PC11
+#define SPI3_MISO_PIN PB5
+
+#define GYRO_1_ALIGN CW90_DEG
+#define ACC_1_ALIGN GYRO_1_ALIGN
+#define GYRO_1_CS_PIN PB2
+#define GYRO_1_EXTI_PIN PC4
+#define GYRO_1_SPI_INSTANCE SPI1
+#define GYRO_2_ALIGN CW90_DEG
+#define ACC_2_ALIGN GYRO_2_ALIGN
+#define GYRO_2_CS_PIN PA4
+#define GYRO_2_EXTI_PIN PC3
+#define GYRO_2_SPI_INSTANCE SPI1
+
+#define USE_DUAL_GYRO
+
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define ACC_MPU6000_ALIGN GYRO_1_ALIGN
+#define GYRO_MPU6000_ALIGN GYRO_1_ALIGN
+#define MPU6000_CS_PIN GYRO_1_CS_PIN
+#define MPU6000_SPI_INSTANCE GYRO_1_SPI_INSTANCE
+#define MPU_INT_EXTI GYRO_1_EXTI_PIN
+
+#define ACC_ICM20689_ALIGN GYRO_1_ALIGN
+#define GYRO_ICM20689_ALIGN GYRO_1_ALIGN
+#define ICM20689_CS_PIN GYRO_1_CS_PIN
+#define ICM20689_SPI_INSTANCE GYRO_1_SPI_INSTANCE
+
+#define ACC_ICM42688P_ALIGN GYRO_1_ALIGN
+#define GYRO_ICM42688P_ALIGN GYRO_1_ALIGN
+#define ICM42688P_CS_PIN GYRO_1_CS_PIN
+#define ICM42688P_SPI_INSTANCE GYRO_1_SPI_INSTANCE
+
+// notice - this file was programmatically generated and may need GYRO_2 manually added.
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define BARO_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB6
+#define I2C1_SDA PB7
+
+#define FLASH_CS_PIN PC13
+#define FLASH_SPI_INSTANCE SPI3
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PB12
+#define MAX7456_SPI_INSTANCE SPI2
+
+#define USE_UART1
+#define USE_UART2
+#define USE_UART3
+#define USE_UART4
+#define USE_UART5
+#define USE_UART6
+#define UART1_TX_PIN PA9
+#define UART2_TX_PIN PA2
+#define UART3_TX_PIN PB10
+#define UART4_TX_PIN PA0
+#define UART5_TX_PIN PC12
+#define UART6_TX_PIN PC6
+#define UART1_RX_PIN PA10
+#define UART2_RX_PIN PA3
+#define UART3_RX_PIN PB11
+#define UART4_RX_PIN PA1
+#define UART5_RX_PIN PD2
+#define UART6_RX_PIN PC7
+#define SERIAL_PORT_COUNT 6
+
+//manually edited
+#define RX_PPM_PIN PA3
+
+// notice - UART/USART were programmatically generated - should verify UART/USART.
+// notice - may need "#define SERIALRX_UART SERIAL_PORT_USART_"
+// notice - should verify serial count.
+
+#define VBAT_ADC_PIN PC2
+#define CURRENT_METER_ADC_PIN PC1
+#define RSSI_ADC_PIN PC0
+#define ADC3_DMA_STREAM DMA2_Stream1 //manually edited Stream1
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 450
+
+#define ENABLE_DSHOT_DMAR true
+
+// notice - this file was programmatically generated and did not account for any potential LEDx_INVERTED, inverted Telem, etc.
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - must verify last port group for 0xffff or (BIT(2))
+
+#define USABLE_TIMER_CHANNEL_COUNT 9
+#define USED_TIMERS ( TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4)|TIM_N(8)|TIM_N(9) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/JHEF_JHEF7DUAL/target.mk b/src/main/target/JHEF_JHEF7DUAL/target.mk
new file mode 100644
index 0000000000..fad227d9b0
--- /dev/null
+++ b/src/main/target/JHEF_JHEF7DUAL/target.mk
@@ -0,0 +1,13 @@
+F7X5XG_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_mpu.c \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/accgyro/accgyro_spi_icm20689.c \
+drivers/accgyro/accgyro_spi_icm426xx.c \
+drivers/barometer/barometer_bmp280.c \
+drivers/max7456.c
+
+# notice - this file was programmatically generated and may be incomplete.
+# eg: flash, compass, barometer, vtx6705, ledstrip, pinio, etc.
From b071d659effa0c9aeb0f1deeeaa30c5ee4e6c108 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Fri, 26 May 2023 11:44:35 -0500
Subject: [PATCH 10/22] ICM42688P - JHEF_JHEF7DUAL; WIP; not working; no USB
connect
---
src/main/target/JHEF_JHEF7DUAL/target.h | 2 ++
src/main/target/JHEF_JHEF7DUAL/target.mk | 5 ++++-
2 files changed, 6 insertions(+), 1 deletion(-)
diff --git a/src/main/target/JHEF_JHEF7DUAL/target.h b/src/main/target/JHEF_JHEF7DUAL/target.h
index 89c57a5e80..53c5a542e4 100644
--- a/src/main/target/JHEF_JHEF7DUAL/target.h
+++ b/src/main/target/JHEF_JHEF7DUAL/target.h
@@ -42,6 +42,8 @@
#define USE_VCP
#define USE_FLASHFS
+#define USE_BEEPER
+#define USE_USB_DETECT
#define USE_LED
#define LED0_PIN PA15
diff --git a/src/main/target/JHEF_JHEF7DUAL/target.mk b/src/main/target/JHEF_JHEF7DUAL/target.mk
index fad227d9b0..20bd3ca95a 100644
--- a/src/main/target/JHEF_JHEF7DUAL/target.mk
+++ b/src/main/target/JHEF_JHEF7DUAL/target.mk
@@ -7,7 +7,10 @@ drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_icm20689.c \
drivers/accgyro/accgyro_spi_icm426xx.c \
drivers/barometer/barometer_bmp280.c \
-drivers/max7456.c
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/light_ws2811strip_hal.c \
+drivers/max7456.c \
# notice - this file was programmatically generated and may be incomplete.
# eg: flash, compass, barometer, vtx6705, ledstrip, pinio, etc.
From ed9dc776d77dcd98114a52293c4a5c888a190aae Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Fri, 26 May 2023 14:20:26 -0500
Subject: [PATCH 11/22] ICM426xx - add CRAZYFLIE2 to unsupported targets due to
build failure and obsolescence
---
make/targets.mk | 2 ++
1 file changed, 2 insertions(+)
diff --git a/make/targets.mk b/make/targets.mk
index ef439980d3..bc7a71fccd 100644
--- a/make/targets.mk
+++ b/make/targets.mk
@@ -34,6 +34,8 @@ UNSUPPORTED_TARGETS := \
CRAZYBEEF3DX \
CRAZYBEEF3FR \
CRAZYBEEF3FS \
+ CRAZYFLIE2 \
+ CRAZYFLIE2BQ \
DOGE EACHIF3 \
FF_ACROWHOOPSP \
FF_KOMBINI \
From cd6e9e3f27a800de098bc6dc19567b3e1341315d Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Fri, 26 May 2023 15:29:09 -0500
Subject: [PATCH 12/22] ICM426xx - fix out of band #endif
---
src/main/drivers/bus_spi.c | 3 ++-
1 file changed, 2 insertions(+), 1 deletion(-)
diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c
index d0da693b6e..c0dc1078d9 100644
--- a/src/main/drivers/bus_spi.c
+++ b/src/main/drivers/bus_spi.c
@@ -251,7 +251,6 @@ void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance) {
bus->bustype = BUSTYPE_SPI;
bus->busdev_u.spi.instance = instance;
}
-#endif
uint16_t spiCalculateDivider(uint32_t freq)
@@ -279,3 +278,5 @@ uint8_t spiReadRegMsk(const busDevice_t *bus, uint8_t reg)
{
return spiBusReadRegister(bus, reg | 0x80);
}
+
+#endif
From 8c7ac7321a80179df229cbd159cf1c6d90fea843 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Fri, 26 May 2023 15:40:09 -0500
Subject: [PATCH 13/22] ICM42688P - JHEF_JHEF7DUAL; WIP; untested
---
src/main/target/JHEF_JHEF7DUAL/target.mk | 1 +
1 file changed, 1 insertion(+)
diff --git a/src/main/target/JHEF_JHEF7DUAL/target.mk b/src/main/target/JHEF_JHEF7DUAL/target.mk
index 20bd3ca95a..42381e10fb 100644
--- a/src/main/target/JHEF_JHEF7DUAL/target.mk
+++ b/src/main/target/JHEF_JHEF7DUAL/target.mk
@@ -10,6 +10,7 @@ drivers/barometer/barometer_bmp280.c \
drivers/light_led.h \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c \
+drivers/pinio.c \
drivers/max7456.c \
# notice - this file was programmatically generated and may be incomplete.
From 3c25c29364a6757b05ce3676c437f42d8a1f2af1 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Sat, 27 May 2023 11:34:58 -0500
Subject: [PATCH 14/22] ICM42688P - modded existing JHEF7DUAL; new
JHEF_JHEF7DUAL is not working
---
src/main/target/JHEF7DUAL/target.h | 7 +++++++
src/main/target/JHEF7DUAL/target.mk | 1 +
src/main/target/JHEF_JHEF7DUAL/target.c | 4 +++-
src/main/target/JHEF_JHEF7DUAL/target.h | 13 +++++++++++--
src/main/target/JHEF_JHEF7DUAL/target.mk | 1 +
5 files changed, 23 insertions(+), 3 deletions(-)
diff --git a/src/main/target/JHEF7DUAL/target.h b/src/main/target/JHEF7DUAL/target.h
index e7e4e5c221..90066ad91e 100644
--- a/src/main/target/JHEF7DUAL/target.h
+++ b/src/main/target/JHEF7DUAL/target.h
@@ -53,10 +53,12 @@
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
#define USE_GYRO_SPI_ICM20689
+#define USE_GYRO_SPI_ICM42688P
#define USE_ACC
#define USE_ACC_SPI_MPU6000
#define USE_ACC_SPI_ICM20689
+#define USE_ACC_SPI_ICM42688P
#define ACC_ICM20689_1_ALIGN CW90_DEG
#define GYRO_ICM20689_1_ALIGN CW90_DEG
@@ -68,6 +70,11 @@
#define GYRO_2_ALIGN GYRO_MPU6000_2_ALIGN
#define ACC_2_ALIGN ACC_MPU6000_2_ALIGN
+#define ACC_ICM42688P_ALIGN CW90_DEG
+#define GYRO_ICM42688P_ALIGN CW90_DEG
+#define GYRO_1_ALIGN ACC_ICM42688P_ALIGN
+#define ACC_1_ALIGN GYRO_ICM42688P_ALIGN
+
#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1
// *************** Baro **************************
diff --git a/src/main/target/JHEF7DUAL/target.mk b/src/main/target/JHEF7DUAL/target.mk
index 8b16c3f1b2..42e86d325d 100644
--- a/src/main/target/JHEF7DUAL/target.mk
+++ b/src/main/target/JHEF7DUAL/target.mk
@@ -5,6 +5,7 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_icm20689.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
drivers/barometer/barometer_bmp280.c \
drivers/compass/compass_fake.c \
drivers/light_ws2811strip.c \
diff --git a/src/main/target/JHEF_JHEF7DUAL/target.c b/src/main/target/JHEF_JHEF7DUAL/target.c
index 82501da5ce..2ca22f1929 100644
--- a/src/main/target/JHEF_JHEF7DUAL/target.c
+++ b/src/main/target/JHEF_JHEF7DUAL/target.c
@@ -29,7 +29,7 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
/* notice - incomplete */
// format : DEF_TIM(TIMxx, CHx, Pxx, TIM_USE_xxxxxxx, x, x), //comment
- DEF_TIM(TIM9, CH2, PA3, TIM_USE_LED, 0, 0), //LED0
+ DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), //LED0
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // #define MOTOR1_PIN PB0
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // #define MOTOR2_PIN PB1
@@ -43,6 +43,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
};
+// existing src/main/target/JHEF7DUAL contains TIM_USE_PPM, not TIM_USE_LED for TIM9-CH2-PA3
+
// TIM_USE options:
// TIM_USE_ANY
// TIM_USE_BEEPER
diff --git a/src/main/target/JHEF_JHEF7DUAL/target.h b/src/main/target/JHEF_JHEF7DUAL/target.h
index 53c5a542e4..476c192ef5 100644
--- a/src/main/target/JHEF_JHEF7DUAL/target.h
+++ b/src/main/target/JHEF_JHEF7DUAL/target.h
@@ -104,6 +104,7 @@
#define USE_I2C
#define USE_I2C_DEVICE_1
+#define I2C_DEVICE (I2CDEV_1) //manually added
#define BARO_I2C_INSTANCE (I2CDEV_1)
#define I2C1_SCL PB6
#define I2C1_SDA PB7
@@ -145,19 +146,27 @@
#define VBAT_ADC_PIN PC2
#define CURRENT_METER_ADC_PIN PC1
#define RSSI_ADC_PIN PC0
-#define ADC3_DMA_STREAM DMA2_Stream1 //manually edited Stream1
+// #define ADC3_DMA_STREAM DMA2_Stream0 //manually edited to _Stream1 // commented out, does not exist in existing target
+#define ADC3_DMA_OPT 0 // DMA 2 Stream 0 Channel 2 //copied from existing target
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
#define DEFAULT_CURRENT_METER_SCALE 450
#define ENABLE_DSHOT_DMAR true
+// manually added from existing target
+// note - existing target has config.c referencing PINIO as well - unsure why it is needed
+#define USE_PINIO
+#define PINIO1_PIN PC14 // VTX power switcher
+#define PINIO2_PIN PB9 // 2xCamera switcher
+#define USE_PINIOBOX
+
// notice - this file was programmatically generated and did not account for any potential LEDx_INVERTED, inverted Telem, etc.
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
-#define TARGET_IO_PORTD 0xffff
+#define TARGET_IO_PORTD (BIT(2)) // manually modified from existing target
// notice - masks were programmatically generated - must verify last port group for 0xffff or (BIT(2))
#define USABLE_TIMER_CHANNEL_COUNT 9
diff --git a/src/main/target/JHEF_JHEF7DUAL/target.mk b/src/main/target/JHEF_JHEF7DUAL/target.mk
index 42381e10fb..07a894d2f5 100644
--- a/src/main/target/JHEF_JHEF7DUAL/target.mk
+++ b/src/main/target/JHEF_JHEF7DUAL/target.mk
@@ -15,3 +15,4 @@ drivers/max7456.c \
# notice - this file was programmatically generated and may be incomplete.
# eg: flash, compass, barometer, vtx6705, ledstrip, pinio, etc.
+# existing src/main/target/JHEF7DUAL contains compass_fake, does not contain light_led, does not contain pinio
\ No newline at end of file
From de8f05a5a56cdeae9bcf38486f55829bff5dc515 Mon Sep 17 00:00:00 2001
From: BeauBrewski <85623381+BeauBrewski@users.noreply.github.com>
Date: Sun, 28 May 2023 10:11:39 -0500
Subject: [PATCH 15/22] ICM466xx - fix BETAFPVF722 target
---
src/main/target/BETAFPVF722/target.c | 4 +---
src/main/target/BETAFPVF722/target.h | 7 ++++---
2 files changed, 5 insertions(+), 6 deletions(-)
diff --git a/src/main/target/BETAFPVF722/target.c b/src/main/target/BETAFPVF722/target.c
index 1af98e92f5..b2aeb61ba6 100644
--- a/src/main/target/BETAFPVF722/target.c
+++ b/src/main/target/BETAFPVF722/target.c
@@ -28,8 +28,7 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// FILO arrangement for motor assignments, Motor 1 starts at 2nd DECLARATION
- DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), // USE FOR CAMERA CONTROL
-
+
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // D1-ST0 MOTOR1
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // D1-ST3 MOTOR2
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, 0, 0), // D1-ST7 MOTOR3
@@ -38,5 +37,4 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // NONE TIM4_UP_D1-ST6 MOTOR6
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // D1-ST2 LED/MOTOR5
-
};
diff --git a/src/main/target/BETAFPVF722/target.h b/src/main/target/BETAFPVF722/target.h
index a3afa80eb3..595a08c5f2 100644
--- a/src/main/target/BETAFPVF722/target.h
+++ b/src/main/target/BETAFPVF722/target.h
@@ -33,7 +33,7 @@
#define BEEPER_INVERTED
//define camera control
-#define CAMERA_CONTROL_PIN PC8
+// N/A
//MPU-6000
#define USE_GYRO
@@ -130,6 +130,7 @@
#define VBAT_ADC_PIN PC0
#define RSSI_ADC_PIN PC2
#define CURRENT_METER_SCALE_DEFAULT 450 // 3.3/120A = 25mv/A
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// SPI devices
#define USE_SPI
@@ -164,5 +165,5 @@
#define TARGET_IO_PORTD (BIT(2))
// timers
-#define USABLE_TIMER_CHANNEL_COUNT 8
-#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) )
+#define USABLE_TIMER_CHANNEL_COUNT 7
+#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) )
From cd92f98a6226b840013f54a9ae70f30b70fcdd1c Mon Sep 17 00:00:00 2001
From: BeauBrewski <85623381+BeauBrewski@users.noreply.github.com>
Date: Sun, 28 May 2023 10:20:10 -0500
Subject: [PATCH 16/22] ICM466xx - fix JHEF_JHEF7DUAL target
---
src/main/target/JHEF_JHEF7DUAL/target.mk | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/src/main/target/JHEF_JHEF7DUAL/target.mk b/src/main/target/JHEF_JHEF7DUAL/target.mk
index 07a894d2f5..47046c055b 100644
--- a/src/main/target/JHEF_JHEF7DUAL/target.mk
+++ b/src/main/target/JHEF_JHEF7DUAL/target.mk
@@ -1,4 +1,4 @@
-F7X5XG_TARGETS += $(TARGET)
+F7X2RE_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
From c18e54a453a0025d6ac763b829be79f57f78a19f Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Tue, 30 May 2023 15:30:15 -0500
Subject: [PATCH 17/22] ICM426xx - gyro_hardware_lpf modes
---
src/main/interface/settings.c | 5 +++++
1 file changed, 5 insertions(+)
diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c
index 42db3695c7..ba2e16d294 100644
--- a/src/main/interface/settings.c
+++ b/src/main/interface/settings.c
@@ -252,8 +252,13 @@ static const char * const lookupTableRxSpi[] = {
static const char * const lookupTableGyroHardwareLpf[] = {
"NORMAL",
+#if defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P)
+ "OPTION1",
+ "OPTION2"
+#else
"EXPERIMENTAL",
"1KHZ_SAMPLING"
+#endif
};
#ifdef USE_32K_CAPABLE_GYRO
From beb0cf81eeccad2e11092c6710468c725faadb42 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Wed, 31 May 2023 15:17:12 -0500
Subject: [PATCH 18/22] ICM426xx - define USE_GYRO_DLPF_EXPERIMENTAL
---
src/main/drivers/accgyro/accgyro.h | 9 ++++++++-
src/main/interface/settings.c | 7 +++++--
src/main/target/common_fc_pre.h | 3 +++
3 files changed, 16 insertions(+), 3 deletions(-)
diff --git a/src/main/drivers/accgyro/accgyro.h b/src/main/drivers/accgyro/accgyro.h
index 7c15965ba6..263880accb 100644
--- a/src/main/drivers/accgyro/accgyro.h
+++ b/src/main/drivers/accgyro/accgyro.h
@@ -38,15 +38,22 @@
#endif
#define GYRO_HARDWARE_LPF_NORMAL 0
-#define GYRO_HARDWARE_LPF_EXPERIMENTAL 1
#define GYRO_HARDWARE_LPF_1KHZ_SAMPLE 2
+#if defined(USE_GYRO_SPI_ICM42688P)
+#define GYRO_HARDWARE_LPF_EXPERIMENTAL 3
+#else
+#define GYRO_HARDWARE_LPF_EXPERIMENTAL 1
+#endif
+
#define GYRO_32KHZ_HARDWARE_LPF_NORMAL 0
#define GYRO_32KHZ_HARDWARE_LPF_EXPERIMENTAL 1
#define GYRO_HARDWARE_LPF_OPTION_1 1
#define GYRO_HARDWARE_LPF_OPTION_2 2
+
+
#define GYRO_LPF_256HZ 0
#define GYRO_LPF_188HZ 1
#define GYRO_LPF_98HZ 2
diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c
index ba2e16d294..3db9b37e84 100644
--- a/src/main/interface/settings.c
+++ b/src/main/interface/settings.c
@@ -254,10 +254,13 @@ static const char * const lookupTableGyroHardwareLpf[] = {
"NORMAL",
#if defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P)
"OPTION1",
- "OPTION2"
+ "OPTION2",
+#if defined(USE_GYRO_SPI_ICM42688P) && defined(USE_GYRO_DLPF_EXPERIMENTAL) // will need bmi270 logic as well
+ "EXPERIMENTAL",
+#endif
#else
"EXPERIMENTAL",
- "1KHZ_SAMPLING"
+ "1KHZ_SAMPLING",
#endif
};
diff --git a/src/main/target/common_fc_pre.h b/src/main/target/common_fc_pre.h
index 2345ab8aba..426ec9b767 100644
--- a/src/main/target/common_fc_pre.h
+++ b/src/main/target/common_fc_pre.h
@@ -228,3 +228,6 @@
#define USE_CMS_FAILSAFE_MENU
#define USE_CMS_GPS_RESCUE_MENU
#endif
+
+// ICM42688P define
+#define USE_GYRO_DLPF_EXPERIMENTAL
From fa49fa6d01ec1b9779ee53d6219214839c0220ec Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Wed, 31 May 2023 15:29:11 -0500
Subject: [PATCH 19/22] ICM426xx - add ICM42605_CS_PIN
---
src/main/drivers/accgyro/accgyro_spi_icm426xx.c | 2 +-
src/main/pg/bus_spi.c | 3 +++
2 files changed, 4 insertions(+), 1 deletion(-)
diff --git a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c
index eedaf23c27..0c90f38d31 100644
--- a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c
+++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c
@@ -68,7 +68,7 @@
#define ICM426XX_RA_ACCEL_CONFIG_STATIC4 0x05 // User Bank 2
// --- Register & setting for gyro and acc UI Filter --------
#define ICM426XX_RA_GYRO_ACCEL_CONFIG0 0x52 // User Bank 0
-#define ICM426XX_ACCEL_UI_FILT_BW_LOW_LATENCY (15 << 4)
+#define ICM426XX_ACCEL_UI_FILT_BW_LOW_LATENCY (15 << 4)
#define ICM426XX_GYRO_UI_FILT_BW_LOW_LATENCY (15 << 0)
// ----------------------------------------------------------
diff --git a/src/main/pg/bus_spi.c b/src/main/pg/bus_spi.c
index 3f8beca26c..3b1fcfa7a8 100644
--- a/src/main/pg/bus_spi.c
+++ b/src/main/pg/bus_spi.c
@@ -91,6 +91,9 @@ ioTag_t preinitIPUList[SPI_PREINIT_IPU_COUNT] = {
#ifdef ICM20689_CS_PIN
IO_TAG(ICM20689_CS_PIN),
#endif
+#ifdef ICM42605_CS_PIN
+ IO_TAG(ICM42605_CS_PIN),
+#endif
#ifdef ICM42688P_CS_PIN
IO_TAG(ICM42688P_CS_PIN),
#endif
From 2a3b82083dc2d0155a202ea984a2e6282f38afdd Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Wed, 31 May 2023 15:52:24 -0500
Subject: [PATCH 20/22] ICM426xx - remove comma in lookupTableGyroHardwareLpf
---
src/main/interface/settings.c | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c
index 3db9b37e84..9634ec73c8 100644
--- a/src/main/interface/settings.c
+++ b/src/main/interface/settings.c
@@ -260,7 +260,7 @@ static const char * const lookupTableGyroHardwareLpf[] = {
#endif
#else
"EXPERIMENTAL",
- "1KHZ_SAMPLING",
+ "1KHZ_SAMPLING"
#endif
};
From 12b28650c63eb8df82195d2f712a6da6c8be840a Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Thu, 1 Jun 2023 08:49:17 -0500
Subject: [PATCH 21/22] ICM426xx - target resets and removal
---
make/targets.mk | 2 -
src/main/target/BETAFPVF722/target.c | 4 +-
src/main/target/BETAFPVF722/target.h | 17 +-
src/main/target/BETAFPVF722/target.mk | 1 -
src/main/target/DIAT_MAMBAF405_2022B/target.c | 100 ----------
src/main/target/DIAT_MAMBAF405_2022B/target.h | 154 ---------------
.../target/DIAT_MAMBAF405_2022B/target.mk | 14 --
src/main/target/FOXEERF722V4/target.c | 45 -----
src/main/target/FOXEERF722V4/target.h | 154 ---------------
src/main/target/FOXEERF722V4/target.mk | 13 --
src/main/target/FOXEERF745V3_AIO/target.c | 40 ----
src/main/target/FOXEERF745V3_AIO/target.h | 161 ----------------
src/main/target/FOXEERF745V3_AIO/target.mk | 12 --
src/main/target/GEPRC_F722_AIO/target.c | 45 -----
src/main/target/GEPRC_F722_AIO/target.h | 158 ----------------
src/main/target/GEPRC_F722_AIO/target.mk | 15 --
src/main/target/JHEF7DUAL/target.h | 7 -
src/main/target/JHEF7DUAL/target.mk | 1 -
src/main/target/JHEF_JHEF7DUAL/target.c | 119 ------------
src/main/target/JHEF_JHEF7DUAL/target.h | 175 ------------------
src/main/target/JHEF_JHEF7DUAL/target.mk | 18 --
src/main/target/RUSH_BLADE_F7_HD/target.h | 6 -
src/main/target/RUSH_BLADE_F7_HD/target.mk | 1 -
23 files changed, 6 insertions(+), 1256 deletions(-)
delete mode 100644 src/main/target/DIAT_MAMBAF405_2022B/target.c
delete mode 100644 src/main/target/DIAT_MAMBAF405_2022B/target.h
delete mode 100644 src/main/target/DIAT_MAMBAF405_2022B/target.mk
delete mode 100644 src/main/target/FOXEERF722V4/target.c
delete mode 100644 src/main/target/FOXEERF722V4/target.h
delete mode 100644 src/main/target/FOXEERF722V4/target.mk
delete mode 100644 src/main/target/FOXEERF745V3_AIO/target.c
delete mode 100644 src/main/target/FOXEERF745V3_AIO/target.h
delete mode 100644 src/main/target/FOXEERF745V3_AIO/target.mk
delete mode 100644 src/main/target/GEPRC_F722_AIO/target.c
delete mode 100644 src/main/target/GEPRC_F722_AIO/target.h
delete mode 100644 src/main/target/GEPRC_F722_AIO/target.mk
delete mode 100644 src/main/target/JHEF_JHEF7DUAL/target.c
delete mode 100644 src/main/target/JHEF_JHEF7DUAL/target.h
delete mode 100644 src/main/target/JHEF_JHEF7DUAL/target.mk
diff --git a/make/targets.mk b/make/targets.mk
index bc7a71fccd..ef439980d3 100644
--- a/make/targets.mk
+++ b/make/targets.mk
@@ -34,8 +34,6 @@ UNSUPPORTED_TARGETS := \
CRAZYBEEF3DX \
CRAZYBEEF3FR \
CRAZYBEEF3FS \
- CRAZYFLIE2 \
- CRAZYFLIE2BQ \
DOGE EACHIF3 \
FF_ACROWHOOPSP \
FF_KOMBINI \
diff --git a/src/main/target/BETAFPVF722/target.c b/src/main/target/BETAFPVF722/target.c
index b2aeb61ba6..1af98e92f5 100644
--- a/src/main/target/BETAFPVF722/target.c
+++ b/src/main/target/BETAFPVF722/target.c
@@ -28,7 +28,8 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// FILO arrangement for motor assignments, Motor 1 starts at 2nd DECLARATION
-
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), // USE FOR CAMERA CONTROL
+
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // D1-ST0 MOTOR1
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // D1-ST3 MOTOR2
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, 0, 0), // D1-ST7 MOTOR3
@@ -37,4 +38,5 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // NONE TIM4_UP_D1-ST6 MOTOR6
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // D1-ST2 LED/MOTOR5
+
};
diff --git a/src/main/target/BETAFPVF722/target.h b/src/main/target/BETAFPVF722/target.h
index 595a08c5f2..31821bc7b2 100644
--- a/src/main/target/BETAFPVF722/target.h
+++ b/src/main/target/BETAFPVF722/target.h
@@ -33,7 +33,7 @@
#define BEEPER_INVERTED
//define camera control
-// N/A
+#define CAMERA_CONTROL_PIN PC8
//MPU-6000
#define USE_GYRO
@@ -49,16 +49,6 @@
#define GYRO_MPU6000_ALIGN CW180_DEG
#define ACC_MPU6000_ALIGN CW180_DEG
-
-// ICM42688P
-#define USE_GYRO_SPI_ICM42688P
-#define USE_ACC_SPI_ICM42688P
-#define ICM42688P_CS_PIN PA4
-#define ICM42688P_SPI_INSTANCE SPI1
-#define GYRO_ICM42688P_ALIGN CW180_DEG
-#define ACC_ICM42688P_ALIGN CW180_DEG
-
-
// OSD
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI3
@@ -130,7 +120,6 @@
#define VBAT_ADC_PIN PC0
#define RSSI_ADC_PIN PC2
#define CURRENT_METER_SCALE_DEFAULT 450 // 3.3/120A = 25mv/A
-#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// SPI devices
#define USE_SPI
@@ -165,5 +154,5 @@
#define TARGET_IO_PORTD (BIT(2))
// timers
-#define USABLE_TIMER_CHANNEL_COUNT 7
-#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) )
+#define USABLE_TIMER_CHANNEL_COUNT 8
+#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) )
diff --git a/src/main/target/BETAFPVF722/target.mk b/src/main/target/BETAFPVF722/target.mk
index 0da79a44b5..56beeaedad 100644
--- a/src/main/target/BETAFPVF722/target.mk
+++ b/src/main/target/BETAFPVF722/target.mk
@@ -4,7 +4,6 @@ FEATURES = VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_mpu.c \
-drivers/accgyro/accgyro_spi_icm426xx.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
diff --git a/src/main/target/DIAT_MAMBAF405_2022B/target.c b/src/main/target/DIAT_MAMBAF405_2022B/target.c
deleted file mode 100644
index 7d472b3254..0000000000
--- a/src/main/target/DIAT_MAMBAF405_2022B/target.c
+++ /dev/null
@@ -1,100 +0,0 @@
-/*
- * This file is part of EmuFlight. It is derived from Betaflight.
- *
- * This 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.
- *
- * This software 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 .
- */
-
-#include
-#include "platform.h"
-#include "drivers/io.h"
-#include "drivers/dma.h"
-#include "drivers/timer.h"
-#include "drivers/timer_def.h"
-
-const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
-/* notice - incomplete */
- DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP,
- //DEF_TIM(TIM4, CH3, PB8, TIM_USE_ANY, 0, 0), // baro/mag // no dps310 in EmuFlight,
- //DEF_TIM(TIM11, CH1, PB9, TIM_USE_ANY, 0, 0), // baro/mag // no dps310 in EmuFlight,
- DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR, 0, 0 ), // M1
- DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0 ), // M2
- DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0 ), // M3
- DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0 ), // M4
- DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0 ), // M5
- DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0 ), // M6
-};
-// notice - this file was programmatically generated and may be incomplete.
-
-// #define MOTOR1_PIN PA9
-// #define MOTOR2_PIN PA8
-// #define MOTOR3_PIN PC9
-// #define MOTOR4_PIN PC8
-// #define MOTOR5_PIN PB0
-// #define MOTOR6_PIN PB1
-
-// #define TIMER_PIN_MAPPING \
-// TIMER_PIN_MAP( 0, PB9 , 2, -1) \
-// TIMER_PIN_MAP( 1, PA9 , 1, 0) \ //m1
-// TIMER_PIN_MAP( 2, PA8 , 1, 0) \ //m2
-// TIMER_PIN_MAP( 3, PC9 , 2, 0) \ //m3
-// TIMER_PIN_MAP( 4, PC8 , 2, 0) \ //m4
-// TIMER_PIN_MAP( 5, PB0 , 2, 0) \ //m5
-// TIMER_PIN_MAP( 6, PB1 , 2, 0) \ //m6
-// TIMER_PIN_MAP( 7, PB8 , 1, 0) \ //I2C1_SCL_PIN //baro/mag?
-// TIMER_PIN_MAP( 8, PB3 , 1, 0) //LED_STRIP_PIN
-
-// # timer
-// timer B09 AF3
-// # pin B09: TIM11 CH1 (AF3) //baro/mag
-// timer A09 AF1
-// # pin A09: TIM1 CH2 (AF1) //m1
-// timer A08 AF1
-// # pin A08: TIM1 CH1 (AF1) //m2
-// timer C09 AF3
-// # pin C09: TIM8 CH4 (AF3) //m3
-// timer C08 AF3
-// # pin C08: TIM8 CH3 (AF3) //m4
-// timer B00 AF2
-// # pin B00: TIM3 CH3 (AF2) //m5
-// timer B01 AF2
-// # pin B01: TIM3 CH4 (AF2) //m6
-// timer B08 AF2
-// # pin B08: TIM4 CH3 (AF2) //baro/mag
-// timer B03 AF1
-// # pin B03: TIM2 CH2 (AF1) //led
-//
-// # dma
-// dma ADC 3 0
-// # ADC 3: DMA2 Stream 0 Channel 2
-// dma pin A09 0
-// # pin A09: DMA2 Stream 6 Channel 0
-// dma pin A08 0
-// # pin A08: DMA2 Stream 6 Channel 0
-// dma pin C09 0
-// # pin C09: DMA2 Stream 7 Channel 7
-// dma pin C08 0
-// # pin C08: DMA2 Stream 2 Channel 0
-// dma pin B00 0
-// # pin B00: DMA1 Stream 7 Channel 5
-// dma pin B01 0
-// # pin B01: DMA1 Stream 2 Channel 5
-// dma pin B08 0
-// # pin B08: DMA1 Stream 7 Channel 2
-// dma pin B03 0
-// # pin B03: DMA1 Stream 6 Channel 3
-
diff --git a/src/main/target/DIAT_MAMBAF405_2022B/target.h b/src/main/target/DIAT_MAMBAF405_2022B/target.h
deleted file mode 100644
index c96f78e383..0000000000
--- a/src/main/target/DIAT_MAMBAF405_2022B/target.h
+++ /dev/null
@@ -1,154 +0,0 @@
-/*
- * This file is part of EmuFlight. It is derived from Betaflight.
- *
- * This 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.
- *
- * This software 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 "DIAT"
-#define USBD_PRODUCT_STRING "MAMBAF405_2022B"
-
-#define USE_ACC
-#define USE_ACC_SPI_MPU6000
-#define USE_GYRO
-#define USE_GYRO_SPI_MPU6000
-#define USE_ACC_SPI_MPU6500
-#define USE_GYRO_SPI_MPU6500
-#define USE_GYRO_SPI_ICM42688P
-#define USE_ACC_SPI_ICM42688P
-#define USE_BARO_DPS310
-#define USE_FLASH
-#define USE_FLASHFS
-#define USE_FLASH_M25P16
-#define USE_MAX7456
-#define USE_BARO
-#define USE_ADC
-#define USE_SPI_GYRO
-// manual
-#define USE_VCP
-#define USE_SERIAL_4WAY_BLHELI_INTERFACE
-
-#define USE_LED
-#define LED0_PIN PC15
-#define LED1_PIN PC14
-#define BEEPER_PIN PC13
-#define BEEPER_INVERTED
-
-#define USE_SPI
-#define USE_SPI_DEVICE_1
-#define SPI1_SCK_PIN PA5
-#define SPI1_MOSI_PIN PA6
-#define SPI1_MISO_PIN PA7
-#define USE_SPI_DEVICE_2
-#define SPI2_SCK_PIN PB13
-#define SPI2_MOSI_PIN PB14
-#define SPI2_MISO_PIN PB15
-#define USE_SPI_DEVICE_3
-#define SPI3_SCK_PIN PC10
-#define SPI3_MOSI_PIN PC11
-#define SPI3_MISO_PIN PB5
-
-#define USE_EXTI
-
-#define GYRO_1_ALIGN CW270_DEG
-#define GYRO_1_CS_PIN PA4
-#define GYRO_1_EXTI_PIN PC4
-#define GYRO_1_SPI_INSTANCE SPI1
-
-#define USE_MPU_DATA_READY_SIGNAL
-
-#define ACC_MPU6000_ALIGN GYRO_1_ALIGN
-#define GYRO_MPU6000_ALIGN GYRO_1_ALIGN
-#define MPU6000_CS_PIN GYRO_1_CS_PIN
-#define MPU6000_SPI_INSTANCE GYRO_1_SPI_INSTANCE
-#define MPU_INT_EXTI GYRO_1_EXTI_PIN
-
-#define ACC_MPU6500_ALIGN GYRO_1_ALIGN
-#define GYRO_MPU6500_ALIGN GYRO_1_ALIGN
-#define MPU6500_CS_PIN GYRO_1_CS_PIN
-#define MPU6500_SPI_INSTANCE GYRO_1_SPI_INSTANCE
-#define MPU_INT_EXTI GYRO_1_EXTI_PIN
-
-#define ACC_ICM42688P_ALIGN GYRO_1_ALIGN
-#define GYRO_ICM42688P_ALIGN GYRO_1_ALIGN
-#define ICM42688P_CS_PIN GYRO_1_CS_PIN
-#define ICM42688P_SPI_INSTANCE GYRO_1_SPI_INSTANCE
-
-// notice - this file was programmatically generated and may need GYRO_2 manually added.
-
-#define USE_I2C
-#define USE_I2C_DEVICE_1
-#define MAG_I2C_INSTANCE (I2CDEV_1)
-#define BARO_I2C_INSTANCE (I2CDEV_1)
-#define I2C1_SCL PB8
-#define I2C1_SDA PB9
-
-#define FLASH_CS_PIN PA15
-#define FLASH_SPI_INSTANCE SPI3
-#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
-
-#define MAX7456_SPI_CS_PIN PB12
-#define MAX7456_SPI_INSTANCE SPI2
-
-#define UART1_TX_PIN PB6
-#define UART2_TX_PIN PA2
-#define UART3_TX_PIN PB10
-#define UART4_TX_PIN PA0
-#define UART5_TX_PIN PC12
-#define UART6_TX_PIN PC6
-#define UART1_RX_PIN PB7
-#define UART2_RX_PIN PA3
-#define UART3_RX_PIN PB11
-#define UART4_RX_PIN PA1
-#define UART5_RX_PIN PD2
-#define UART6_RX_PIN PC7
-#define INVERTER_PIN_UART1 PC0
-#define SERIAL_PORT_COUNT 6
-// notice - UART/USART were programmatically generated - must check USART validity.${hFile}
-// notice - may need "#define SERIALRX_UART SERIAL_PORT_USART_"
-// notice - should check serial count.
-
-//manual
-#define USE_UART1
-#define USE_UART2
-#define USE_UART3
-#define USE_UART4
-#define USE_UART5
-#define USE_UART6
-
-
-#define VBAT_ADC_PIN PC1
-#define CURRENT_METER_ADC_PIN PC3
-#define ADC3_DMA_STREAM DMA2_Stream0 // notice - DMA2_Stream0 likely need correcting, please modify.
-#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
-#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
-#define DEFAULT_CURRENT_METER_SCALE 183
-
-#define ENABLE_DSHOT_DMAR true
-
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC 0xffff
-#define TARGET_IO_PORTD 0xffff
-// notice - masks were programmatically generated - must verify last port group for 0xffff or (BIT(2))
-
-#define USABLE_TIMER_CHANNEL_COUNT 9
-#define USED_TIMERS ( TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4)|TIM_N(8)|TIM_N(11)) /* notice - incomplete */
-
-// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/DIAT_MAMBAF405_2022B/target.mk b/src/main/target/DIAT_MAMBAF405_2022B/target.mk
deleted file mode 100644
index 418c2fce24..0000000000
--- a/src/main/target/DIAT_MAMBAF405_2022B/target.mk
+++ /dev/null
@@ -1,14 +0,0 @@
-F405_TARGETS += $(TARGET)
-FEATURES += VCP ONBOARDFLASH
-
-TARGET_SRC = \
-drivers/accgyro/accgyro_mpu.c \
-drivers/accgyro/accgyro_mpu6500.c \
-drivers/accgyro/accgyro_spi_mpu6000.c \
-drivers/accgyro/accgyro_spi_mpu6500.c \
-drivers/accgyro/accgyro_spi_icm426xx.c \
-drivers/max7456.c
-
-# notice - this file was programmatically generated and may be incomplete.
-# eg: flash, compass, barometer, vtx6705, ledstrip, pinio, etc.
-
diff --git a/src/main/target/FOXEERF722V4/target.c b/src/main/target/FOXEERF722V4/target.c
deleted file mode 100644
index f0ad3a1f43..0000000000
--- a/src/main/target/FOXEERF722V4/target.c
+++ /dev/null
@@ -1,45 +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 .
- */
-
-#include
-
-#include "platform.h"
-#include "drivers/io.h"
-
-#include "drivers/dma.h"
-#include "drivers/timer.h"
-#include "drivers/timer_def.h"
-
-const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
- DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM&SBUS
-
- DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR, 0, 0), // S1
- DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0), // S2
- DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // S3
- DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // S4
- DEF_TIM(TIM8, CH1, PC6, TIM_USE_ANY, 0, 0), // TX6
- DEF_TIM(TIM8, CH2, PC7, TIM_USE_ANY, 0, 0), // RX6
-
-
- DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED STRIP(1,5)
-
- DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // FC CAM
-
-};
diff --git a/src/main/target/FOXEERF722V4/target.h b/src/main/target/FOXEERF722V4/target.h
deleted file mode 100644
index 1ceef9ed9e..0000000000
--- a/src/main/target/FOXEERF722V4/target.h
+++ /dev/null
@@ -1,154 +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
-
-#define TARGET_BOARD_IDENTIFIER "FXF7"
-#define USBD_PRODUCT_STRING "FOXEERF722V4"
-
-#define USE_GYRO
-#define USE_ACC
-#define USE_EXTI
-//#define USE_GYRO_SPI_MPU6000
-//#define USE_ACC_SPI_MPU6000
-#define USE_GYRO_SPI_ICM42688P
-#define USE_ACC_SPI_ICM42688P
-
-#define MPU_INT_EXTI PC4
-#define MPU6000_CS_PIN PB2
-#define ICM42688P_CS_PIN PB2
-#define MPU6000_SPI_INSTANCE SPI1
-#define ICM42688P_SPI_INSTANCE SPI1
-#define GYRO_MPU6000_ALIGN CW270_DEG
-#define GYRO_ICM42688P_ALIGN CW270_DEG
-#define ACC_MPU6000_ALIGN CW270_DEG
-#define ACC_ICM42688P_ALIGN CW270_DEG
-
-#define USE_MPU_DATA_READY_SIGNAL
-#define ENSURE_MPU_DATA_READY_IS_LOW
-
-#define ENABLE_DSHOT_DMAR true
-#define LED0_PIN PC15
-
-#define USE_BEEPER
-#define BEEPER_PIN PA4
-#define BEEPER_INVERTED
-
-#define CAMERA_CONTROL_PIN PB3
-
-#define USE_BARO
-#define USE_BARO_MS5611
-#define USE_BARO_BMP280
-#define BARO_I2C_INSTANCE (I2CDEV_1)
-
-#define USE_MAG
-#define USE_MAG_HMC5883
-#define MAG_I2C_INSTANCE (I2CDEV_1)
-
-
-#define USE_VCP
-#define USE_UART1
-#define USE_UART2
-#define USE_UART3
-#define USE_UART4
-#define USE_UART5
-#define USE_UART6
-
-#define UART1_TX_PIN PB6
-#define UART1_RX_PIN PB7
-
-#define UART2_TX_PIN PA2
-#define UART2_RX_PIN PA3
-
-#define UART3_TX_PIN PB10
-#define UART3_RX_PIN PB11
-
-#define UART4_TX_PIN PA0
-#define UART4_RX_PIN PA1
-
-#define UART5_TX_PIN PC12
-#define UART5_RX_PIN PD2
-
-#define UART6_TX_PIN PC6
-#define UART6_RX_PIN PC7
-
-#define SERIAL_PORT_COUNT 7
-
-#define USE_I2C
-#define USE_I2C_DEVICE_1
-#define I2C_DEVICE I2CDEV_1
-#define I2C1_SCL PB8
-#define I2C1_SDA PB9
-
-#define USE_SPI
-
-#define USE_SPI_DEVICE_1 // 2xGYRO/ACC
-#define SPI1_SCK_PIN PA5
-#define SPI1_MISO_PIN PA6
-#define SPI1_MOSI_PIN PA7
-
-#define USE_SPI_DEVICE_2 // FLASH
-#define SPI2_SCK_PIN PB13
-#define SPI2_MISO_PIN PB14
-#define SPI2_MOSI_PIN PB15
-
-#define USE_MAX7456
-#define MAX7456_SPI_INSTANCE SPI3
-#define MAX7456_SPI_CS_PIN PC3
-
-#define USE_SPI_DEVICE_3 // MAX7456
-#define SPI3_SCK_PIN PC10
-#define SPI3_MISO_PIN PC11
-#define SPI3_MOSI_PIN PB5
-
-#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
-#define USE_FLASHFS
-#define USE_FLASH_W25M512
-#define USE_FLASH_M25P16
-#define FLASH_CS_PIN PB12
-#define FLASH_SPI_INSTANCE SPI2
-
-#define USE_ADC
-#define ADC_INSTANCE ADC3
-#define ADC3_DMA_STREAM DMA2_Stream0
-
-#define VBAT_ADC_PIN PC0
-#define CURRENT_METER_ADC_PIN PC2
-#define RSSI_ADC_PIN PA0
-
-#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
-#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
-
-#define USE_OSD
-#define USE_LED_STRIP
-
-#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
-#define DEFAULT_FEATURES FEATURE_OSD
-#define SERIALRX_UART SERIAL_PORT_USART1
-#define SERIALRX_PROVIDER SERIALRX_SBUS
-
-
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC 0xffff
-#define TARGET_IO_PORTD 0xffff
-
-#define USABLE_TIMER_CHANNEL_COUNT 9
-#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(4) |TIM_N(8) )
diff --git a/src/main/target/FOXEERF722V4/target.mk b/src/main/target/FOXEERF722V4/target.mk
deleted file mode 100644
index 3f80ab3aa5..0000000000
--- a/src/main/target/FOXEERF722V4/target.mk
+++ /dev/null
@@ -1,13 +0,0 @@
-F7X2RE_TARGETS += $(TARGET)
-FEATURES += VCP ONBOARDFLASH
-
-TARGET_SRC = \
- drivers/barometer/barometer_bmp280.c \
- drivers/barometer/barometer_ms5611.c \
- drivers/compass/compass_hmc5883l.c \
- drivers/max7456.c \
- drivers/accgyro/accgyro_mpu6500.c \
- drivers/accgyro/accgyro_spi_mpu6000.c \
- drivers/accgyro/accgyro_spi_mpu6500.c \
- drivers/accgyro/accgyro_mpu.c \
- drivers/accgyro/accgyro_spi_icm426xx.c
diff --git a/src/main/target/FOXEERF745V3_AIO/target.c b/src/main/target/FOXEERF745V3_AIO/target.c
deleted file mode 100644
index bbdaad53be..0000000000
--- a/src/main/target/FOXEERF745V3_AIO/target.c
+++ /dev/null
@@ -1,40 +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 .
- */
-
-#include
-
-#include "platform.h"
-#include "drivers/io.h"
-
-#include "drivers/dma.h"
-#include "drivers/timer.h"
-#include "drivers/timer_def.h"
-
-const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
-
-DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0 ), // LED_STRIP,
-DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // CAMCONTR,
-
-DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0 ), // M1
-DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0 ), // M2
-DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0 ), // M3
-DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0 ), // M4
-
- };
diff --git a/src/main/target/FOXEERF745V3_AIO/target.h b/src/main/target/FOXEERF745V3_AIO/target.h
deleted file mode 100644
index 17acdf78a4..0000000000
--- a/src/main/target/FOXEERF745V3_AIO/target.h
+++ /dev/null
@@ -1,161 +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
-
- #define TARGET_BOARD_IDENTIFIER "FOXE"
- #define USBD_PRODUCT_STRING "FOXEERF745V3_AIO"
-
- #define LED0_PIN PC13
-
- #define USE_BEEPER
- #define BEEPER_PIN PD2
- #define BEEPER_INVERTED
-
- #define CAMERA_CONTROL_PIN PB3
-
- #define ICM42688P_CS_PIN PA15
- #define ICM42688P_SPI_INSTANCE SPI3
-
- #define USE_ACC
- #define USE_ACC_SPI_ICM42688P
- #define ACC_ICM42688P_ALIGN CW180_DEG
-
- #define USE_GYRO
- #define USE_GYRO_SPI_ICM42688P
- #define GYRO_ICM42688P_ALIGN CW180_DEG
-
- // MPU6000 interrupts
- #define USE_MPU_DATA_READY_SIGNAL
- #define MPU_INT_EXTI PD0
- #define USE_EXTI
-
- #define USE_MAG
- #define USE_MAG_HMC5883
- #define USE_MAG_QMC5883
- #define USE_MAG_LIS3MDL
- #define MAG_I2C_INSTANCE (I2CDEV_1)
- //#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
- //#define MAG_ALIGN CW180_DEG //not sure if this command will work or if should be more specific to mag
-
- #define USE_BARO
- #define USE_BARO_BMP280
- #define BARO_I2C_INSTANCE (I2CDEV_1)
-
- #define USE_VCP
- #define USE_USB_DETECT
- //#define USB_DETECT_PIN PA8
-
- #define USE_UART1
- #define UART1_RX_PIN PA10
- #define UART1_TX_PIN PA9
-
- #define USE_UART2
- #define UART2_RX_PIN PA3
- #define UART2_TX_PIN PA2
-
- #define USE_UART3
- #define UART3_RX_PIN PB11
- #define UART3_TX_PIN PB10
-
- #define USE_UART4
- #define UART4_RX_PIN PA1
- #define UART4_TX_PIN PA0
-
- #define USE_UART7
- #define UART7_RX_PIN PE7
- #define UART7_TX_PIN PE8
-
- #define SERIAL_PORT_COUNT 6 //VCP, USART1, USART2, USART3, UART4, USART7
-
- #define USE_ESC_SENSOR
-
- #define USE_SPI
- #define USE_SPI_DEVICE_1 //osd
- #define USE_SPI_DEVICE_2 //?
- #define USE_SPI_DEVICE_3 //gyro
- #define USE_SPI_DEVICE_4 //flash
-
-
- #define SPI1_SCK_PIN PA5
- #define SPI1_MISO_PIN PA6
- #define SPI1_MOSI_PIN PA7
-
-
- #define SPI2_SCK_PIN PB13
- #define SPI2_MISO_PIN PB14
- #define SPI2_MOSI_PIN PB15
-
- #define SPI3_SCK_PIN PC10
- #define SPI3_MISO_PIN PC11
- #define SPI3_MOSI_PIN PC12
-
- #define SPI4_SCK_PIN PE2
- #define SPI4_MISO_PIN PE5
- #define SPI4_MOSI_PIN PE6
-
- #define USE_MAX7456
- #define MAX7456_SPI_INSTANCE SPI1
- #define MAX7456_SPI_CS_PIN PA4
- #define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz
- #define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
-
- //#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
- #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
- #define USE_FLASHFS
- #define USE_FLASH_M25P16
- #define FLASH_CS_PIN PE4
- #define FLASH_SPI_INSTANCE SPI4
-
- #define USE_I2C
- #define USE_I2C_DEVICE_1
- #define I2C_DEVICE_1 (I2CDEV_1)
- #define I2C1_SCL PB8
- #define I2C1_SDA PB9
-
- #define USE_ADC
- #define VBAT_ADC_PIN PC3
- #define CURRENT_METER_ADC_PIN PC2
- #define RSSI_ADC_PIN PC5
- #define EXTERNAL1_ADC_PIN PC1
- #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
- #define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
- #define CURRENT_METER_SCALE_DEFAULT 100
-
- #define USE_LED_STRIP
- #define LED_STRIP_PIN PA8
- #define USE_RX_MSP
-// #define RX_MSP_UART SERIAL_PORT_USART5 //default uart5 MSP on
-
- #define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_OSD)
- #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
- #define SERIALRX_PROVIDER SERIALRX_SBUS
- #define SERIALRX_UART SERIAL_PORT_USART1
- #define USE_DSHOT
-
- #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 USABLE_TIMER_CHANNEL_COUNT 6
-
- #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) )
diff --git a/src/main/target/FOXEERF745V3_AIO/target.mk b/src/main/target/FOXEERF745V3_AIO/target.mk
deleted file mode 100644
index a575053156..0000000000
--- a/src/main/target/FOXEERF745V3_AIO/target.mk
+++ /dev/null
@@ -1,12 +0,0 @@
-F7X5XG_TARGETS += $(TARGET)
-FEATURES += VCP ONBOARDFLASH
-
-TARGET_SRC = \
- drivers/accgyro/accgyro_spi_icm426xx.c \
- drivers/accgyro/accgyro_mpu.c \
- drivers/barometer/barometer_bmp280.c \
- drivers/compass/compass_hmc5883l.c \
- drivers/compass/compass_qmc5883l.c \
- drivers/compass/compass_lis3mdl.c \
- drivers/light_ws2811strip.c \
- drivers/max7456.c
diff --git a/src/main/target/GEPRC_F722_AIO/target.c b/src/main/target/GEPRC_F722_AIO/target.c
deleted file mode 100644
index 2d5f11353a..0000000000
--- a/src/main/target/GEPRC_F722_AIO/target.c
+++ /dev/null
@@ -1,45 +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 .
- */
-
-#include
-
-#include "platform.h"
-#include "drivers/io.h"
-
-#include "drivers/dma.h"
-#include "drivers/timer.h"
-#include "drivers/timer_def.h"
-
-const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
-DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), //CAMERA CONTROL
-DEF_TIM(TIM9, CH2, PA3, TIM_USE_ANY, 0, 0), //PPM
-
-DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), //MOTOR 1
-DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 1), //MOTOR 2
-DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 1), //MOTOR 3
-DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0), //MOTOR 4
-
-//DEF_TIM(TIM4, CH1, PB6, TIM_USE_ANY, 0, 0), //in config but match no pins
-//DEF_TIM(TIM4, CH2, PB7, TIM_USE_ANY, 0, 0), //pretty sure left over from
-//DEF_TIM(TIM3, CH4, PB1, TIM_USE_ANY, 0, 0), //geprc_f722_bthd target/config
-//DEF_TIM(TIM3, CH3, PB0, TIM_USE_ANY, 0, 0), //as match motors 5-8
-
-DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0) //LED
-};
diff --git a/src/main/target/GEPRC_F722_AIO/target.h b/src/main/target/GEPRC_F722_AIO/target.h
deleted file mode 100644
index 2cb368bae7..0000000000
--- a/src/main/target/GEPRC_F722_AIO/target.h
+++ /dev/null
@@ -1,158 +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 .
- *
- * Prepared by Kaio
- */
-#pragma once
-
-#define TARGET_BOARD_IDENTIFIER "S7X2"
-#define USBD_PRODUCT_STRING "GEPRC_F722_AIO"
-#define TARGET_MANUFACTURER_IDENTIFIER "GEPR"
-
-#define LED0_PIN PC4
-
-#define USE_BEEPER
-#define BEEPER_PIN PC15
-#define BEEPER_INVERTED
-
-#define ENABLE_DSHOT_DMAR true
-
-#define USE_EXTI
-#define MPU_INT_EXTI PA8
-#define USE_MPU_DATA_READY_SIGNAL
-
-#define USE_GYRO
-
-#define USE_GYRO_SPI_ICM42688P
-#define ICM42688P_CS_PIN PA15
-#define ICM42688P_SPI_INSTANCE SPI1
-#define GYRO_ICM42688P_ALIGN CW90_DEG
-
-#define USE_GYRO_SPI_MPU6000
-#define MPU6000_CS_PIN PA15
-#define MPU6000_SPI_INSTANCE SPI1
-#define GYRO_MPU6000_ALIGN CW90_DEG
-
-#define USE_ACC
-
-#define USE_ACC_SPI_ICM42688P
-#define ACC_ICM42688P_ALIGN CW90_DEG
-
-#define USE_ACC_SPI_MPU6000
-#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6000_ALIGN CW90_DEG
-
-#define USE_BARO
-#define USE_BARO_BMP280
-#define USE_BARO_BMP085
-#define USE_BARO_MS5611
-#define BARO_I2C_INSTANCE (I2CDEV_2)
-
-#define USE_MAG
-#define USE_MAG_HMC5883
-#define USE_MAG_QMC5883
-#define MAG_I2C_INSTANCE (I2CDEV_2)
-
-#define USE_MAX7456
-#define MAX7456_SPI_INSTANCE SPI2
-#define MAX7456_SPI_CS_PIN PB12
-
-#define USE_FLASHFS
-#define USE_FLASH_M25P16
-#define FLASH_SPI_INSTANCE SPI3
-#define FLASH_CS_PIN PB9
-#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
-
-#define USE_VCP
-#define USE_USB_DETECT
-
-#define USE_UART1
-#define UART1_RX_PIN PA10
-#define UART1_TX_PIN PA9
-
-#define USE_UART2
-#define UART2_RX_PIN PA3
-#define UART2_TX_PIN PA2
-
-#define USE_UART3
-#define UART3_RX_PIN PB11
-#define UART3_TX_PIN PB10
-
-#define USE_UART4
-#define UART4_RX_PIN PC11
-#define UART4_TX_PIN PC10
-
-#define USE_UART5
-#define UART5_RX_PIN PD2
-#define UART5_TX_PIN PC12
-
-#define SERIAL_PORT_COUNT 6 //USB + 5 UARTS
-
-#define USE_ESCSERIAL //PPM
-#define ESCSERIAL_TIMER_TX_PIN PA3
-
-#define USE_SPI
-#define USE_SPI_DEVICE_1
-#define SPI1_SCK_PIN PA5
-#define SPI1_MISO_PIN PA6
-#define SPI1_MOSI_PIN PA7
-
-#define USE_SPI_DEVICE_2
-#define SPI2_SCK_PIN PB13
-#define SPI2_MISO_PIN PB14
-#define SPI2_MOSI_PIN PB15
-
-#define USE_SPI_DEVICE_3
-#define SPI3_SCK_PIN PB3
-#define SPI3_MISO_PIN PB4
-#define SPI3_MOSI_PIN PB5
-
-//#define USE_I2C
-//#define USE_I2C_DEVICE_1
-//#define I2C1_SCL PB8
-//#define I2C1_SDA PB9
-//#define I2C_DEVICE (I2CDEV_1)
-
-#define USE_I2C_DEVICE_2
-#define I2C2_SCL PB10
-#define I2C2_SDA PB11
-#define I2C_DEVICE (I2CDEV_2)
-
-#define USE_ADC
-#define ADC3_DMA_STREAM DMA2_Stream0
-#define VBAT_ADC_PIN PC2
-#define CURRENT_METER_ADC_PIN PC1
-//#define RSSI_ADC_PIN PC2
-#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
-#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
-#define CURRENT_METER_SCALE_DEFAULT 100
-
-#define SERIALRX_PROVIDER SERIALRX_SBUS
-//#define SERIALRX_UART SERIAL_PORT_USART2
-
-#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
-#define DEFAULT_FEATURES ( FEATURE_OSD | FEATURE_TELEMETRY )
-
-#define TARGET_IO_PORTA ( 0xffff )
-#define TARGET_IO_PORTB ( 0xffff )
-#define TARGET_IO_PORTC ( 0xffff )
-#define TARGET_IO_PORTD ( 0xffff )
-
-#define USABLE_TIMER_CHANNEL_COUNT 7
-#define USED_TIMERS ( TIM_N(2) | TIM_N(5) | TIM_N(8) | TIM_N(9) )
diff --git a/src/main/target/GEPRC_F722_AIO/target.mk b/src/main/target/GEPRC_F722_AIO/target.mk
deleted file mode 100644
index 8047e388fd..0000000000
--- a/src/main/target/GEPRC_F722_AIO/target.mk
+++ /dev/null
@@ -1,15 +0,0 @@
-F7X2RE_TARGETS += $(TARGET)
-FEATURES += VCP ONBOARDFLASH
-TARGET_SRC = \
- drivers/accgyro/accgyro_spi_icm426xx.c \
- drivers/accgyro/accgyro_mpu.c \
- drivers/accgyro/accgyro_mpu6500.c \
- drivers/accgyro/accgyro_spi_mpu6000.c \
- drivers/accgyro/accgyro_spi_mpu6500.c \
- drivers/barometer/barometer_ms5611.c \
- drivers/barometer/barometer_bmp280.c \
- drivers/barometer/barometer_bmp085.c \
- drivers/compass/compass_hmc5883l.c \
- drivers/compass/compass_qmc5883l.c \
- drivers/max7456.c\
- drivers/light_ws2811strip.c
diff --git a/src/main/target/JHEF7DUAL/target.h b/src/main/target/JHEF7DUAL/target.h
index 90066ad91e..e7e4e5c221 100644
--- a/src/main/target/JHEF7DUAL/target.h
+++ b/src/main/target/JHEF7DUAL/target.h
@@ -53,12 +53,10 @@
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
#define USE_GYRO_SPI_ICM20689
-#define USE_GYRO_SPI_ICM42688P
#define USE_ACC
#define USE_ACC_SPI_MPU6000
#define USE_ACC_SPI_ICM20689
-#define USE_ACC_SPI_ICM42688P
#define ACC_ICM20689_1_ALIGN CW90_DEG
#define GYRO_ICM20689_1_ALIGN CW90_DEG
@@ -70,11 +68,6 @@
#define GYRO_2_ALIGN GYRO_MPU6000_2_ALIGN
#define ACC_2_ALIGN ACC_MPU6000_2_ALIGN
-#define ACC_ICM42688P_ALIGN CW90_DEG
-#define GYRO_ICM42688P_ALIGN CW90_DEG
-#define GYRO_1_ALIGN ACC_ICM42688P_ALIGN
-#define ACC_1_ALIGN GYRO_ICM42688P_ALIGN
-
#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1
// *************** Baro **************************
diff --git a/src/main/target/JHEF7DUAL/target.mk b/src/main/target/JHEF7DUAL/target.mk
index 42e86d325d..8b16c3f1b2 100644
--- a/src/main/target/JHEF7DUAL/target.mk
+++ b/src/main/target/JHEF7DUAL/target.mk
@@ -5,7 +5,6 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_icm20689.c \
- drivers/accgyro/accgyro_spi_icm426xx.c \
drivers/barometer/barometer_bmp280.c \
drivers/compass/compass_fake.c \
drivers/light_ws2811strip.c \
diff --git a/src/main/target/JHEF_JHEF7DUAL/target.c b/src/main/target/JHEF_JHEF7DUAL/target.c
deleted file mode 100644
index 2ca22f1929..0000000000
--- a/src/main/target/JHEF_JHEF7DUAL/target.c
+++ /dev/null
@@ -1,119 +0,0 @@
-/*
- * This file is part of EmuFlight. It is derived from Betaflight.
- *
- * This 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.
- *
- * This software 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 .
- */
-
-#include
-#include "platform.h"
-#include "drivers/io.h"
-#include "drivers/dma.h"
-#include "drivers/timer.h"
-#include "drivers/timer_def.h"
-
-const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
-/* notice - incomplete */
-// format : DEF_TIM(TIMxx, CHx, Pxx, TIM_USE_xxxxxxx, x, x), //comment
- DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), //LED0
-
- DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // #define MOTOR1_PIN PB0
- DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // #define MOTOR2_PIN PB1
- DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // #define MOTOR3_PIN PB4
- DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR, 0, 0), // #define MOTOR4_PIN PB3
- DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // #define MOTOR5_PIN PC9
- DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // #define MOTOR6_PIN PC8
-
- DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), //LED_STRIP
- DEF_TIM(TIM4, CH3, PB8, TIM_USE_ANY, 0, 0), //CAM_CONTROL
-
-};
-
-// existing src/main/target/JHEF7DUAL contains TIM_USE_PPM, not TIM_USE_LED for TIM9-CH2-PA3
-
-// TIM_USE options:
-// TIM_USE_ANY
-// TIM_USE_BEEPER
-// TIM_USE_LED
-// TIM_USE_MOTOR
-// TIM_USE_NONE
-// TIM_USE_PPM
-// TIM_USE_PWM
-// TIM_USE_SERVO
-// TIM_USE_TRANSPONDER
-
-// config.h resources:
-// #define MOTOR1_PIN PB0
-// #define MOTOR2_PIN PB1
-// #define MOTOR3_PIN PB4
-// #define MOTOR4_PIN PB3
-// #define MOTOR5_PIN PC9
-// #define MOTOR6_PIN PC8
-// #define TIMER_PIN_MAPPING \
-// TIMER_PIN_MAP( 0, PA3 , 3, -1) \
-// TIMER_PIN_MAP( 1, PB0 , 2, 0) \
-// TIMER_PIN_MAP( 2, PB1 , 2, 0) \
-// TIMER_PIN_MAP( 3, PB4 , 1, 0) \
-// TIMER_PIN_MAP( 4, PB3 , 1, 0) \
-// TIMER_PIN_MAP( 5, PC9 , 2, 0) \
-// TIMER_PIN_MAP( 6, PC8 , 2, 0) \
-// TIMER_PIN_MAP( 7, PA8 , 1, 0) \
-// TIMER_PIN_MAP( 8, PB8 , 1, 0)
-
-
-// unified-target:
-// # timer
-// timer A03 AF3
-// # pin A03: TIM9 CH2 (AF3)
-
-// timer B00 AF2
-// # pin B00: TIM3 CH3 (AF2)
-// timer B01 AF2
-// # pin B01: TIM3 CH4 (AF2)
-// timer B04 AF2
-// # pin B04: TIM3 CH1 (AF2)
-// timer B03 AF1
-// # pin B03: TIM2 CH2 (AF1)
-// timer C09 AF3
-// # pin C09: TIM8 CH4 (AF3)
-// timer C08 AF3
-// # pin C08: TIM8 CH3 (AF3)
-
-// timer A08 AF1
-// # pin A08: TIM1 CH1 (AF1)
-// timer B08 AF2
-// # pin B08: TIM4 CH3 (AF2)
-//
-// # dma
-// dma ADC 3 1
-// # ADC 3: DMA2 Stream 1 Channel 2
-// dma pin B00 0
-// # pin B00: DMA1 Stream 7 Channel 5
-// dma pin B01 0
-// # pin B01: DMA1 Stream 2 Channel 5
-// dma pin B04 0
-// # pin B04: DMA1 Stream 4 Channel 5
-// dma pin B03 0
-// # pin B03: DMA1 Stream 6 Channel 3
-// dma pin C09 0
-// # pin C09: DMA2 Stream 7 Channel 7
-// dma pin C08 0
-// # pin C08: DMA2 Stream 2 Channel 0
-// dma pin A08 0
-// # pin A08: DMA2 Stream 6 Channel 0
-// dma pin B08 0
-// # pin B08: DMA1 Stream 7 Channel 2
diff --git a/src/main/target/JHEF_JHEF7DUAL/target.h b/src/main/target/JHEF_JHEF7DUAL/target.h
deleted file mode 100644
index 476c192ef5..0000000000
--- a/src/main/target/JHEF_JHEF7DUAL/target.h
+++ /dev/null
@@ -1,175 +0,0 @@
-/*
- * This file is part of EmuFlight. It is derived from Betaflight.
- *
- * This 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.
- *
- * This software 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 "JHEF"
-#define USBD_PRODUCT_STRING "JHEF7DUAL"
-
-#define USE_ACC
-#define USE_ACC_SPI_MPU6000
-#define USE_GYRO
-#define USE_GYRO_SPI_MPU6000
-#define USE_ACC_SPI_ICM20689
-#define USE_GYRO_SPI_ICM20689
-#define USE_GYRO_SPI_ICM42688P
-#define USE_ACC_SPI_ICM42688P
-#define USE_BARO_BMP280
-#define USE_FLASH
-#define USE_FLASH_M25P16
-#define USE_MAX7456
-#define USE_BARO
-#define USE_ADC
-#define USE_SPI_GYRO
-
-#define USE_VCP
-#define USE_FLASHFS
-#define USE_BEEPER
-#define USE_USB_DETECT
-
-#define USE_LED
-#define LED0_PIN PA15
-#define LED_STRIP_PIN PA8
-#define BEEPER_PIN PC15
-#define BEEPER_INVERTED
-#define CAMERA_CONTROL_PIN PB8
-
-#define USE_SPI
-#define USE_SPI_DEVICE_1
-#define SPI1_SCK_PIN PA5
-#define SPI1_MOSI_PIN PA6
-#define SPI1_MISO_PIN PA7
-#define USE_SPI_DEVICE_2
-#define SPI2_SCK_PIN PB13
-#define SPI2_MOSI_PIN PB14
-#define SPI2_MISO_PIN PB15
-#define USE_SPI_DEVICE_3
-#define SPI3_SCK_PIN PC10
-#define SPI3_MOSI_PIN PC11
-#define SPI3_MISO_PIN PB5
-
-#define GYRO_1_ALIGN CW90_DEG
-#define ACC_1_ALIGN GYRO_1_ALIGN
-#define GYRO_1_CS_PIN PB2
-#define GYRO_1_EXTI_PIN PC4
-#define GYRO_1_SPI_INSTANCE SPI1
-#define GYRO_2_ALIGN CW90_DEG
-#define ACC_2_ALIGN GYRO_2_ALIGN
-#define GYRO_2_CS_PIN PA4
-#define GYRO_2_EXTI_PIN PC3
-#define GYRO_2_SPI_INSTANCE SPI1
-
-#define USE_DUAL_GYRO
-
-#define USE_EXTI
-#define USE_GYRO_EXTI
-
-#define USE_MPU_DATA_READY_SIGNAL
-
-#define ACC_MPU6000_ALIGN GYRO_1_ALIGN
-#define GYRO_MPU6000_ALIGN GYRO_1_ALIGN
-#define MPU6000_CS_PIN GYRO_1_CS_PIN
-#define MPU6000_SPI_INSTANCE GYRO_1_SPI_INSTANCE
-#define MPU_INT_EXTI GYRO_1_EXTI_PIN
-
-#define ACC_ICM20689_ALIGN GYRO_1_ALIGN
-#define GYRO_ICM20689_ALIGN GYRO_1_ALIGN
-#define ICM20689_CS_PIN GYRO_1_CS_PIN
-#define ICM20689_SPI_INSTANCE GYRO_1_SPI_INSTANCE
-
-#define ACC_ICM42688P_ALIGN GYRO_1_ALIGN
-#define GYRO_ICM42688P_ALIGN GYRO_1_ALIGN
-#define ICM42688P_CS_PIN GYRO_1_CS_PIN
-#define ICM42688P_SPI_INSTANCE GYRO_1_SPI_INSTANCE
-
-// notice - this file was programmatically generated and may need GYRO_2 manually added.
-
-#define USE_I2C
-#define USE_I2C_DEVICE_1
-#define I2C_DEVICE (I2CDEV_1) //manually added
-#define BARO_I2C_INSTANCE (I2CDEV_1)
-#define I2C1_SCL PB6
-#define I2C1_SDA PB7
-
-#define FLASH_CS_PIN PC13
-#define FLASH_SPI_INSTANCE SPI3
-#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
-
-#define MAX7456_SPI_CS_PIN PB12
-#define MAX7456_SPI_INSTANCE SPI2
-
-#define USE_UART1
-#define USE_UART2
-#define USE_UART3
-#define USE_UART4
-#define USE_UART5
-#define USE_UART6
-#define UART1_TX_PIN PA9
-#define UART2_TX_PIN PA2
-#define UART3_TX_PIN PB10
-#define UART4_TX_PIN PA0
-#define UART5_TX_PIN PC12
-#define UART6_TX_PIN PC6
-#define UART1_RX_PIN PA10
-#define UART2_RX_PIN PA3
-#define UART3_RX_PIN PB11
-#define UART4_RX_PIN PA1
-#define UART5_RX_PIN PD2
-#define UART6_RX_PIN PC7
-#define SERIAL_PORT_COUNT 6
-
-//manually edited
-#define RX_PPM_PIN PA3
-
-// notice - UART/USART were programmatically generated - should verify UART/USART.
-// notice - may need "#define SERIALRX_UART SERIAL_PORT_USART_"
-// notice - should verify serial count.
-
-#define VBAT_ADC_PIN PC2
-#define CURRENT_METER_ADC_PIN PC1
-#define RSSI_ADC_PIN PC0
-// #define ADC3_DMA_STREAM DMA2_Stream0 //manually edited to _Stream1 // commented out, does not exist in existing target
-#define ADC3_DMA_OPT 0 // DMA 2 Stream 0 Channel 2 //copied from existing target
-#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
-#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
-#define DEFAULT_CURRENT_METER_SCALE 450
-
-#define ENABLE_DSHOT_DMAR true
-
-// manually added from existing target
-// note - existing target has config.c referencing PINIO as well - unsure why it is needed
-#define USE_PINIO
-#define PINIO1_PIN PC14 // VTX power switcher
-#define PINIO2_PIN PB9 // 2xCamera switcher
-#define USE_PINIOBOX
-
-// notice - this file was programmatically generated and did not account for any potential LEDx_INVERTED, inverted Telem, etc.
-
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC 0xffff
-#define TARGET_IO_PORTD (BIT(2)) // manually modified from existing target
-// notice - masks were programmatically generated - must verify last port group for 0xffff or (BIT(2))
-
-#define USABLE_TIMER_CHANNEL_COUNT 9
-#define USED_TIMERS ( TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4)|TIM_N(8)|TIM_N(9) )
-
-// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/JHEF_JHEF7DUAL/target.mk b/src/main/target/JHEF_JHEF7DUAL/target.mk
deleted file mode 100644
index 47046c055b..0000000000
--- a/src/main/target/JHEF_JHEF7DUAL/target.mk
+++ /dev/null
@@ -1,18 +0,0 @@
-F7X2RE_TARGETS += $(TARGET)
-FEATURES += VCP ONBOARDFLASH
-
-TARGET_SRC = \
-drivers/accgyro/accgyro_mpu.c \
-drivers/accgyro/accgyro_spi_mpu6000.c \
-drivers/accgyro/accgyro_spi_icm20689.c \
-drivers/accgyro/accgyro_spi_icm426xx.c \
-drivers/barometer/barometer_bmp280.c \
-drivers/light_led.h \
-drivers/light_ws2811strip.c \
-drivers/light_ws2811strip_hal.c \
-drivers/pinio.c \
-drivers/max7456.c \
-
-# notice - this file was programmatically generated and may be incomplete.
-# eg: flash, compass, barometer, vtx6705, ledstrip, pinio, etc.
-# existing src/main/target/JHEF7DUAL contains compass_fake, does not contain light_led, does not contain pinio
\ No newline at end of file
diff --git a/src/main/target/RUSH_BLADE_F7_HD/target.h b/src/main/target/RUSH_BLADE_F7_HD/target.h
index 66db6bd6ae..1ad1a5f0c1 100644
--- a/src/main/target/RUSH_BLADE_F7_HD/target.h
+++ b/src/main/target/RUSH_BLADE_F7_HD/target.h
@@ -47,22 +47,16 @@
#define MPU_INT_EXTI PA4
#define MPU6000_CS_PIN PC4
- #define ICM42688P_CS_PIN PC4
#define MPU6000_SPI_INSTANCE SPI1
- #define ICM42688P_SPI_INSTANCE SPI1
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
- #define USE_GYRO_SPI_ICM42688P
#define USE_ACC
#define USE_ACC_SPI_MPU6000
- #define USE_ACC_SPI_ICM42688P
#define GYRO_MPU6000_ALIGN CW270_DEG
- #define GYRO_ICM42688P_ALIGN CW270_DEG
#define ACC_MPU6000_ALIGN CW270_DEG
- #define ACC_ICM42688P_ALIGN CW270_DEG
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
diff --git a/src/main/target/RUSH_BLADE_F7_HD/target.mk b/src/main/target/RUSH_BLADE_F7_HD/target.mk
index 521e974eda..3b2730cf37 100644
--- a/src/main/target/RUSH_BLADE_F7_HD/target.mk
+++ b/src/main/target/RUSH_BLADE_F7_HD/target.mk
@@ -4,7 +4,6 @@ FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
- drivers/accgyro/accgyro_spi_icm426xx.c \
drivers/barometer/barometer_ms5611.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_bmp085.c \
From 5a52aa3d4034cbdaed539bde3e1e250fd8d77d41 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Thu, 1 Jun 2023 09:09:18 -0500
Subject: [PATCH 22/22] ICM42688P - extra line removal
---
src/main/drivers/accgyro/accgyro.h | 2 --
src/main/drivers/accgyro/accgyro_spi_icm426xx.c | 1 -
src/main/drivers/bus_spi.c | 1 -
3 files changed, 4 deletions(-)
diff --git a/src/main/drivers/accgyro/accgyro.h b/src/main/drivers/accgyro/accgyro.h
index 263880accb..2c17f4b2f5 100644
--- a/src/main/drivers/accgyro/accgyro.h
+++ b/src/main/drivers/accgyro/accgyro.h
@@ -52,8 +52,6 @@
#define GYRO_HARDWARE_LPF_OPTION_1 1
#define GYRO_HARDWARE_LPF_OPTION_2 2
-
-
#define GYRO_LPF_256HZ 0
#define GYRO_LPF_188HZ 1
#define GYRO_LPF_98HZ 2
diff --git a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c
index 0c90f38d31..24003f9017 100644
--- a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c
+++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c
@@ -38,7 +38,6 @@
#include "drivers/sensor.h"
#include "drivers/time.h"
-
// 24 MHz max SPI frequency
#define ICM426XX_MAX_SPI_CLK_HZ 24000000
diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c
index c0dc1078d9..d42f0e6156 100644
--- a/src/main/drivers/bus_spi.c
+++ b/src/main/drivers/bus_spi.c
@@ -252,7 +252,6 @@ void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance) {
bus->busdev_u.spi.instance = instance;
}
-
uint16_t spiCalculateDivider(uint32_t freq)
{
#if defined(STM32F4) || defined(STM32G4) || defined(STM32F7)