diff --git a/docs/boards/Board - CrazyBeeF3FR.md b/docs/boards/Board - CrazyBeeF3FR.md
new file mode 100644
index 0000000000..ed05243b59
--- /dev/null
+++ b/docs/boards/Board - CrazyBeeF3FR.md
@@ -0,0 +1,74 @@
+# CrazyBee F3 FR
+
+
+## Description
+CrazyBee F3 flight controller is a Highly integrated board for 1S Whoop brushless racing drone.
+It might be the world first Tiny whoop size brushless flight controller which integrated Receiver/4in1 ESC/OSD/Current Meter.
+## MCU, Sensors and Features
+
+### Hardware and Features
+
+ - MCU: STM32F303CCT6
+ - IMU: MPU6000 (SPI)
+ - IMU Interrupt: yes
+ - VCP: yes
+ - OSD: Betaflight OSD
+ - Battery Voltage Sensor: yes
+ - Integrated Voltage Regulator: yes, booster, 5V/800mA
+ - Integrated Current sensor:Max 14A, could be modified to 28A by replace resistor
+ - Integrated Frsky compatible receiver: Frsky_D(D8) and Frsky_X(D16) switchable mode
+ - Buttons: 1 (Receiver bind button)
+ - Integrated 4x Blheli_s ESC: Max 5A per ESC
+ - ESC Connector: 3-pin, PicoBlade 1.25mm pitch
+ - Beeper output: 2-pin, soldering pad
+ - 4 Rx Indicating LEDs: 2 x red and 2 x white
+
+
+
+## Resource mapping
+
+
+| Label | Pin | Timer | DMA | Default | Note |
+|----------------------------|------|-------|-----|-------------|----------------------------------|
+| MPU6000_INT_EXTI | PC13 | | | | |
+| MPU6000_CS_PIN | PA4 | | | | SPI1 |
+| MPU6000_SCK_PIN | PA5 | | | | SPI1 |
+| MPU6000_MISO_PIN | PA6 | | | | SPI1 |
+| MPU6000_MOSI_PIN | PA7 | | | | SPI1 |
+| OSD_CS_PIN | PB1 | | | | SPI1 |
+| OSD_SCK_PIN | PA5 | | | | SPI1 |
+| OSD_MISO_PIN | PA6 | | | | SPI1 |
+| OSD_MOSI_PIN | PA7 | | | | SPI1 |
+| RX_CS_PIN | PB12 | | | | SPI2 |
+| RX_SCK_PIN | PB13 | | | | SPI2 |
+| RX_MISO_PIN | PB14 | | | | SPI2 |
+| RX_MOSI_PIN | PB15 | | | | SPI2 |
+| RX_GDO0_PIN | PA8 | | | | |
+| RX_BIND_PIN | PA9 | | | | |
+| RX_LED_PIN | PA10 | | | | |
+| PWM1 | PB8 | TIM8, CH2 | | | |
+| PWM2 | PB9 | TIM8, CH3 | | | |
+| PWM3 | PA3 | TIM2, CH4 | | | |
+| PWM4 | PA2 | TIM15,CH1 | | | |
+| VBAT_ADC_PIN | PA0 | | | | ADC1 |
+| RSSI_ADC_PIN | PA1 | | | | ADC1 |
+| BEEPER | PC15 | | | | |
+| UART3 TX | PB10 | | | | will add pinout soon |
+| UART3 RX | PB11 | | | | will add pinout soon |
+
+
+## Manufacturers and Distributors
+
+https://www.banggood.com/Racerstar-Crazybee-F3-Flight-Controller-4-IN-1-5A-1S-Blheli_S-ESC-Compatible-Frsky-D8-Receiver-p-1262972.html
+
+## Designers
+
+
+
+## Maintainers
+
+
+## FAQ & Known Issues
+
+## Other Resources
+ User Manual: http://img.banggood.com/file/products/20180209021414Crazybeef3.pdf
\ No newline at end of file
diff --git a/docs/boards/CrazyBeeF3FRbottom.jpg b/docs/boards/CrazyBeeF3FRbottom.jpg
new file mode 100644
index 0000000000..aba8a78694
Binary files /dev/null and b/docs/boards/CrazyBeeF3FRbottom.jpg differ
diff --git a/docs/boards/CrazyBeeF3FRtop.jpg b/docs/boards/CrazyBeeF3FRtop.jpg
new file mode 100644
index 0000000000..04dc04ccfd
Binary files /dev/null and b/docs/boards/CrazyBeeF3FRtop.jpg differ
diff --git a/src/main/target/CRAZYBEEF3FR/target.c b/src/main/target/CRAZYBEEF3FR/target.c
new file mode 100644
index 0000000000..78f7414535
--- /dev/null
+++ b/src/main/target/CRAZYBEEF3FR/target.c
@@ -0,0 +1,34 @@
+/*
+ * 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/timer.h"
+#include "drivers/timer_def.h"
+#include "drivers/dma.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+
+ DEF_TIM(TIM8, CH2, PB8, TIM_USE_MOTOR, 0), // PWM1 - PB8
+ DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, 0), // PWM2 - PB9
+ DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0), // PWM3 - PA3
+ DEF_TIM(TIM15, CH1, PA2, TIM_USE_MOTOR, 0), // PWM4 - PA2
+
+};
diff --git a/src/main/target/CRAZYBEEF3FR/target.h b/src/main/target/CRAZYBEEF3FR/target.h
new file mode 100644
index 0000000000..7e16f0f0a7
--- /dev/null
+++ b/src/main/target/CRAZYBEEF3FR/target.h
@@ -0,0 +1,94 @@
+/*
+ * 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 "CBFR" //
+#define USBD_PRODUCT_STRING "CrazyBee F3 FR"
+#define LED0_PIN PB3
+#define USE_BEEPER
+#define BEEPER_PIN PC15
+#define BEEPER_INVERTED
+
+#define USE_EXTI
+#define MPU_INT_EXTI PC13
+#define USE_MPU_DATA_READY_SIGNAL
+#define MPU6000_SPI_INSTANCE SPI1
+#define MPU6000_CS_PIN PA4
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define GYRO_MPU6000_ALIGN CW90_DEG
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define ACC_MPU6000_ALIGN CW90_DEG
+
+#define USE_VCP
+#define USE_UART3
+#define SERIAL_PORT_COUNT 2
+#define UART3_TX_PIN PB10
+#define UART3_RX_PIN PB11
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_NSS_PIN PA4
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+
+#define USE_SPI_DEVICE_2
+#define SPI2_NSS_PIN PB12
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+
+#define USE_RX_SPI
+#define USE_RX_FRSKY_SPI_D
+#define USE_RX_FRSKY_SPI_X
+#define USE_RX_FRSKY_SPI_TELEMETRY
+#define DEFAULT_RX_FEATURE FEATURE_RX_SPI
+#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_FRSKY_X
+#define RX_SPI_INSTANCE SPI2
+#define RX_NSS_PIN SPI2_NSS_PIN
+#define RX_SCK_PIN SPI2_SCK_PIN
+#define RX_MISO_PIN SPI2_MISO_PIN
+#define RX_MOSI_PIN SPI2_MOSI_PIN
+#define RX_FRSKY_SPI_GDO_0_PIN PA8
+#define RX_FRSKY_SPI_LED_PIN PA10
+#define BINDPLUG_PIN PA9
+
+#define USE_OSD
+#define USE_MAX7456
+#define MAX7456_SPI_INSTANCE SPI1
+#define MAX7456_SPI_CS_PIN PB1
+#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD)
+#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
+
+#define USE_ADC
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define VBAT_ADC_PIN PA0
+#define CURRENT_METER_ADC_PIN PA1
+#define ADC_INSTANCE ADC1
+
+#define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_OSD)
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
+#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
+#define USABLE_TIMER_CHANNEL_COUNT 4
+#define USED_TIMERS (TIM_N(2) | TIM_N(8) | TIM_N(15))
diff --git a/src/main/target/CRAZYBEEF3FR/target.mk b/src/main/target/CRAZYBEEF3FR/target.mk
new file mode 100644
index 0000000000..367faa2ad4
--- /dev/null
+++ b/src/main/target/CRAZYBEEF3FR/target.mk
@@ -0,0 +1,12 @@
+F3_TARGETS += $(TARGET)
+
+FEATURES = VCP
+
+TARGET_SRC = \
+ drivers/accgyro/accgyro_mpu.c \
+ drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/rx/rx_cc2500.c \
+ rx/cc2500_frsky_shared.c \
+ rx/cc2500_frsky_d.c \
+ rx/cc2500_frsky_x.c \
+ drivers/max7456.c
\ No newline at end of file