diff --git a/src/main/target/YUPIF7/config.c b/src/main/target/YUPIF7/config.c
deleted file mode 100644
index 7438ca8fe3..0000000000
--- a/src/main/target/YUPIF7/config.c
+++ /dev/null
@@ -1,38 +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
-
-#include "platform.h"
-
-#ifdef USE_TARGET_CONFIG
-#include "fc/config.h"
-
-#include "sensors/boardalignment.h"
-
-
-// alternative defaults settings for YuPiF4 targets
-void targetConfiguration(void)
-{
- boardAlignmentMutable()->yawDegrees = 90;
-}
-#endif
-
diff --git a/src/main/target/YUPIF7/target.c b/src/main/target/YUPIF7/target.c
index aaa6e777ec..728a1e5e41 100644
--- a/src/main/target/YUPIF7/target.c
+++ b/src/main/target/YUPIF7/target.c
@@ -22,19 +22,20 @@
#include "platform.h"
#include "drivers/io.h"
+
+#include "drivers/dma.h"
#include "drivers/timer.h"
#include "drivers/timer_def.h"
-#include "drivers/dma.h"
-
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PPM, 0, 0 ), // PPM IN
- DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR, 0, 0 ), // S1_OUT - DMA1_ST2
+ DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 0 ), // S1_OUT - DMA1_ST2
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0 ), // S2_OUT - DMA1_ST4
- DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0 ), // S3_OUT - DMA1_ST1
- DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1 ), // S4_OUT - DMA1_ST6
+ DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR, 0, 0 ), // S3_OUT - DMA1_ST1
+ DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR, 0, 1 ), // S4_OUT - DMA1_ST6
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0 ), // S5_OUT - DMA1_ST7 - LED Control
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_LED, 0, 0 ), // S6_OUT
DEF_TIM(TIM4, CH2, PB7, TIM_USE_ANY, 0, 0 ), // Camera Control
DEF_TIM(TIM12, CH1, PB14, TIM_USE_BEEPER, 0, 0 ), // BEEPER PWM
};
+
diff --git a/src/main/target/YUPIF7/target.h b/src/main/target/YUPIF7/target.h
index 1c04265539..b60f3151c6 100644
--- a/src/main/target/YUPIF7/target.h
+++ b/src/main/target/YUPIF7/target.h
@@ -20,10 +20,11 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "YPF7"
-#define USE_TARGET_CONFIG
#define USBD_PRODUCT_STRING "YUPIF7"
+#define ENABLE_DSHOT_DMAR true
+
#define LED0_PIN PB4
//define camera control
@@ -31,26 +32,32 @@
#define USE_BEEPER
#define BEEPER_PIN PB14
-#define BEEPER_PWM_HZ 3150 // Beeper PWM frequency in Hz
+#define BEEPER_PWM_HZ 3150
-// Gyro interrupt
-#define USE_EXTI
-#define USE_MPU_DATA_READY_SIGNAL
-#define MPU_INT_EXTI PC4
+// *************** Gyro & ACC **********************
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
-// ICM 20689
#define ICM20689_CS_PIN PA4
#define ICM20689_SPI_INSTANCE SPI1
-#define USE_ACC
-#define USE_ACC_SPI_ICM20689
-#define ACC_ICM20689_ALIGN CW90_DEG
+#define USE_EXTI
+#define MPU_INT_EXTI PC4
+#define USE_MPU_DATA_READY_SIGNAL
#define USE_GYRO
#define USE_GYRO_SPI_ICM20689
#define GYRO_ICM20689_ALIGN CW90_DEG
-// Serial ports
+#define USE_ACC
+#define USE_ACC_SPI_ICM20689
+#define ACC_ICM20689_ALIGN CW90_DEG
+
+// *************** UART ****************************
#define USE_VCP
#define USE_USB_DETECT
#define USB_DETECT_PIN PA8
@@ -77,63 +84,59 @@
#define SERIAL_PORT_COUNT 6 //VCP, USART1, USART3, USART5, USART6, SOFTSERIAL1
-#define USE_ESCSERIAL
-#define ESCSERIAL_TIMER_TX_PIN PC8 // (Hardware=0, PPM)
-
-//SPI ports
-#define USE_SPI
-
-#define USE_SPI_DEVICE_1 //Gyro & OSD
-#define SPI1_NSS_PIN PA4
-#define SPI1_SCK_PIN PA5
-#define SPI1_MISO_PIN PA6
-#define SPI1_MOSI_PIN PA7
-
-#define USE_SPI_DEVICE_3 //Dataslash
+// *************** Dataflash ***********************
+#define USE_SPI_DEVICE_3
#define SPI3_NSS_PIN PA15
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PB5
-/* I2C Port
+#define USE_FLASHFS
+#define USE_FLASH_M25P16
+#define FLASH_CS_PIN PA15
+#define FLASH_SPI_INSTANCE SPI3
+
+// *************** Baro ****************************
#define USE_I2C
-#define USE_I2C_PULLUP
#define USE_I2C_DEVICE_1
+#define USE_I2C_PULLUP
#define I2C2_SCL PB8
#define I2C2_SDA PB9
#define I2C_DEVICE (I2CDEV_1)
-*/
-// OSD
+#define BARO_I2C_INSTANCE (I2CDEV_1)
+#define USE_BARO
+#define USE_BARO_BMP280
+#define USE_BARO_MS5611
+
+//*********** Magnetometer / Compass *************
+#define USE_MAG
+#define USE_MAG_HMC5883
+#define USE_MAG_QMC5883
+
+// *************** OSD *****************************
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI1
#define MAX7456_SPI_CS_PIN PA14
-#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz
-#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
-// Dataflash
-#define USE_FLASHFS
-#define USE_FLASH_M25P16
-#define FLASH_CS_PIN SPI3_NSS_PIN
-#define FLASH_SPI_INSTANCE SPI3
-
-// ADC inputs
+// *************** ADC *****************************
#define USE_ADC
-#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
-#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define ADC1_DMA_STREAM DMA2_Stream0
#define RSSI_ADC_GPIO_PIN PC0
#define VBAT_ADC_PIN PC1
#define CURRENT_METER_ADC_PIN PC2
#define CURRENT_METER_SCALE_DEFAULT 235
-// Default configuration
+
+// *************** Target Config *******************
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART6
-#define TELEMETRY_UART SERIAL_PORT_USART1
-#define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_OSD)
+#define DEFAULT_FEATURES (FEATURE_OSD)
-// Target IO and timers
+#define USE_ESCSERIAL
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
@@ -142,4 +145,4 @@
#define TARGET_IO_PORTD (BIT(2))
#define USABLE_TIMER_CHANNEL_COUNT 9
-#define USED_TIMERS (TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(12))
+#define USED_TIMERS (TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(12))
diff --git a/src/main/target/YUPIF7/target.mk b/src/main/target/YUPIF7/target.mk
index 49f2102b8c..8ae0bb21f6 100644
--- a/src/main/target/YUPIF7/target.mk
+++ b/src/main/target/YUPIF7/target.mk
@@ -5,6 +5,5 @@ TARGET_SRC = \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
- drivers/light_ws2811strip.c \
- drivers/light_ws2811strip_hal.c \
+ drivers/compass/compass_qmc5883l.c \
drivers/max7456.c