diff --git a/docs/Board - KroozX.md b/docs/Board - KroozX.md
new file mode 100755
index 0000000000..7167489c3b
--- /dev/null
+++ b/docs/Board - KroozX.md
@@ -0,0 +1,23 @@
+# Board - KroozX
+
+
+
+## Features
+
+* MCU: STM32F4RGT6
+* IMU: MPU6000 (SPI bus), ICM20608 (I2C bus)
+* BARO: MS5611
+* VCP: Yes
+* Hardware UARTS: 5 (RX6/RX1/TX1 with onboard inverters)
+* PWM outputs: 10
+* OSD: MAX7456 with a switch for 2 video channel
+* Blackbox: MicroSD card slot (SD/SDHC, upto 64GB)
+* PPM/SBUS: RX6 with onboard inverter
+* Wireless: HC-12 onboard transceiver
+* Battery Voltage Sensor: Yes, up to 6S input
+* Current Sensor: Yes
+* Integrated Voltage Regulator: 5V 2000mA, 10V 2000mA with LC filter
+* Buttons: No (powering the board with plugged USB starts STM DFU bootloader)
+* Buzzer driver: Yes
+* RSSI Analog/PWM port: Yes
+* SWD port: Yes (SWIO, SWCLK, RST pins)
\ No newline at end of file
diff --git a/src/main/target/KROOZX/hardware_setup.c b/src/main/target/KROOZX/hardware_setup.c
new file mode 100755
index 0000000000..9b20362e52
--- /dev/null
+++ b/src/main/target/KROOZX/hardware_setup.c
@@ -0,0 +1,37 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it 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 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 Cleanflight. If not, see .
+ */
+
+#include
+#include
+#include "platform.h"
+
+#include "drivers/io_impl.h"
+
+#ifdef USE_HARDWARE_PREBOOT_SETUP
+void initialisePreBootHardware(void)
+{
+ // Pulling down OSD switch pin
+ IOInit(DEFIO_IO(OSD_CH_SWITCH), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
+ IOConfigGPIO(DEFIO_IO(OSD_CH_SWITCH), IOCFG_OUT_PP);
+ IOLo(DEFIO_IO(OSD_CH_SWITCH));
+
+ // Inverting the UART1 port by default
+ IOInit(DEFIO_IO(PB13), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
+ IOConfigGPIO(DEFIO_IO(PB13), IOCFG_OUT_PP);
+ IOHi(DEFIO_IO(PB13));
+}
+#endif
diff --git a/src/main/target/KROOZX/target.c b/src/main/target/KROOZX/target.c
new file mode 100755
index 0000000000..2467186c2e
--- /dev/null
+++ b/src/main/target/KROOZX/target.c
@@ -0,0 +1,97 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it 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 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 Cleanflight. If not, see .
+ */
+
+#include
+
+#include
+#include "drivers/io.h"
+#include "drivers/pwm_mapping.h"
+#include "drivers/timer.h"
+
+const uint16_t multiPPM[] = {
+ PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
+ PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
+ 0xFFFF
+};
+
+const uint16_t multiPWM[] = {
+ PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
+ PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
+ 0xFFFF
+};
+
+const uint16_t airPPM[] = {
+ PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
+ PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
+ 0xFFFF
+};
+
+const uint16_t airPWM[] = {
+ PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
+ PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
+ 0xFFFF
+};
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ {TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8 }, // PPM IN
+ {TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5 }, // PWM4
+ {TIM5, IO_TAG(PA3), TIM_Channel_4, TIM5_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5 }, // PWM2
+ {TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5 }, // PWM3
+ {TIM5, IO_TAG(PA2), TIM_Channel_3, TIM5_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5 }, // PWM1
+ {TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // PWM5
+ {TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // PWM6
+ {TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM4 }, // PWM7
+ {TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM4 }, // PWM8
+ {TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM12}, // PWM9
+ {TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM12}, // PWM10
+};
diff --git a/src/main/target/KROOZX/target.h b/src/main/target/KROOZX/target.h
new file mode 100755
index 0000000000..312904221d
--- /dev/null
+++ b/src/main/target/KROOZX/target.h
@@ -0,0 +1,165 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it 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 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 Cleanflight. If not, see .
+ */
+
+#pragma once
+
+#define TARGET_BOARD_IDENTIFIER "KROOZX"
+#define USBD_PRODUCT_STRING "KroozX"
+
+#define USE_HARDWARE_PREBOOT_SETUP
+
+#define LED0 PA14 // Red LED
+#define LED1 PA13 // Green LED
+
+#define BEEPER PC1
+#define BEEPER_INVERTED
+
+#define INVERTER PB12
+#define INVERTER_USART USART6
+
+#define INVERTER_PIN_UART1 PB13
+#define INVERTER_PIN_UART6 PB12
+
+#define MPU6000_CS_PIN PB2
+#define MPU6000_SPI_INSTANCE SPI1
+
+// MPU6000 interrupts
+#define USE_EXTI
+#define USE_MPU_DATA_READY_SIGNAL
+#define MPU_INT_EXTI PA4
+
+#define GYRO
+#define USE_GYRO_SPI_MPU6000
+#define GYRO_MPU6000_ALIGN CW90_DEG_FLIP
+
+#define ACC
+#define USE_ACC_SPI_MPU6000
+#define ACC_MPU6000_ALIGN CW90_DEG_FLIP
+
+#define MAG
+#define USE_MAG_HMC5883
+#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
+#define MAG_I2C_INSTANCE I2CDEV_1
+
+#define BARO
+#define USE_BARO_MS5611
+
+#define USE_SDCARD
+#define SDCARD_DETECT_INVERTED
+#define SDCARD_DETECT_PIN PC13
+#define SDCARD_SPI_INSTANCE SPI3
+#define SDCARD_SPI_CS_PIN PA15
+#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
+#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
+
+#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
+#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF5
+#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
+#define SDCARD_DMA_CHANNEL DMA_Channel_0
+
+#define OSD
+#ifdef USE_MSP_DISPLAYPORT
+#undef USE_MSP_DISPLAYPORT
+#endif
+#define USE_MAX7456
+#define MAX7456_SPI_INSTANCE SPI1
+#define MAX7456_SPI_CS_PIN PC4
+#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD*2)
+#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
+
+#define OSD_CH_SWITCH PC5
+
+#define BOARD_HAS_VOLTAGE_DIVIDER
+#define USE_ADC
+#define VBAT_ADC_PIN PC3
+#define CURRENT_METER_ADC_PIN PC2
+#define RSSI_ADC_PIN PC0
+
+#define USE_VCP
+
+#define USE_UART1
+#define UART1_RX_PIN PA10
+#define UART1_TX_PIN PA9
+
+#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 USE_UART6
+#define UART6_RX_PIN PC7
+#define UART6_TX_PIN PC6
+
+#define SERIAL_PORT_COUNT 6
+
+#define USE_I2C
+#define I2C_DEVICE (I2CDEV_3)
+#define I2C_DEVICE_EXT (I2CDEV_1)
+#define I2C1_SCL PB6
+#define I2C1_SDA PB7
+#define I2C3_SCL PA8
+#define I2C3_SDA PC9
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_NSS_PIN PC4
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PB3
+#define SPI3_MISO_PIN PB4
+#define SPI3_MOSI_PIN PB5
+
+#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
+
+#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
+
+#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
+#define RX_CHANNELS_TAER
+#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_OSD)
+
+#define LED_STRIP
+#define WS2811_GPIO_AF GPIO_AF_TIM3
+#define WS2811_PIN PC6
+#define WS2811_TIMER TIM3
+#define WS2811_TIMER_CHANNEL TIM_Channel_1
+#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST4_HANDLER
+#define WS2811_DMA_STREAM DMA1_Stream4
+#define WS2811_DMA_CHANNEL DMA_Channel_5
+#define WS2811_DMA_IRQ DMA1_Stream4_IRQn
+#define WS2811_DMA_FLAG DMA_FLAG_TCIF4
+#define WS2811_DMA_IT DMA_IT_TCIF4
+
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD (BIT(2))
+
+#define MAX_PWM_OUTPUT_PORTS 10
+#define USABLE_TIMER_CHANNEL_COUNT 11
+#define USED_TIMERS (TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(12))
diff --git a/src/main/target/KROOZX/target.mk b/src/main/target/KROOZX/target.mk
new file mode 100755
index 0000000000..2af4174b5d
--- /dev/null
+++ b/src/main/target/KROOZX/target.mk
@@ -0,0 +1,11 @@
+F405_TARGETS += $(TARGET)
+FEATURES += VCP SDCARD
+HSE_VALUE = 16000000
+
+TARGET_SRC = \
+ drivers/accgyro_spi_mpu6000.c \
+ drivers/barometer_ms56xx.c \
+ drivers/compass_hmc5883l.c \
+ drivers/max7456.c \
+ drivers/light_ws2811strip.c \
+ drivers/light_ws2811strip_stm32f4xx.c
\ No newline at end of file
diff --git a/src/main/target/system_stm32f4xx.c b/src/main/target/system_stm32f4xx.c
index 0e664e8540..536ab1987c 100644
--- a/src/main/target/system_stm32f4xx.c
+++ b/src/main/target/system_stm32f4xx.c
@@ -371,7 +371,7 @@ uint32_t hse_value = HSE_VALUE;
/************************* PLL Parameters *************************************/
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx)
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
-#if defined(COLIBRI)
+#if defined(COLIBRI) || defined(KROOZX)
#define PLL_M 16
#elif defined(PIXRACER)
#define PLL_M 24