diff --git a/src/main/target/NAZE/config.c b/src/main/target/ALIENFLIGHTF1/config.c
similarity index 100%
rename from src/main/target/NAZE/config.c
rename to src/main/target/ALIENFLIGHTF1/config.c
diff --git a/src/main/target/ALIENFLIGHTF1/target.c b/src/main/target/ALIENFLIGHTF1/target.c
new file mode 100644
index 0000000000..7116b53551
--- /dev/null
+++ b/src/main/target/ALIENFLIGHTF1/target.c
@@ -0,0 +1,106 @@
+/*
+ * 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"
+
+const uint16_t multiPPM[] = {
+ PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
+ PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
+ PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
+ PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
+ PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
+ PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
+ PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
+ 0xFFFF
+};
+
+const uint16_t multiPWM[] = {
+ PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
+ PWM2 | (MAP_TO_PWM_INPUT << 8),
+ PWM3 | (MAP_TO_PWM_INPUT << 8),
+ PWM4 | (MAP_TO_PWM_INPUT << 8),
+ PWM5 | (MAP_TO_PWM_INPUT << 8),
+ PWM6 | (MAP_TO_PWM_INPUT << 8),
+ PWM7 | (MAP_TO_PWM_INPUT << 8),
+ PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
+ PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
+ PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
+ PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
+ PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
+ 0xFFFF
+};
+
+const uint16_t airPPM[] = {
+ PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
+ PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
+ PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
+ PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
+ PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
+ PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5
+ PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8
+ 0xFFFF
+};
+
+const uint16_t airPWM[] = {
+ PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
+ PWM2 | (MAP_TO_PWM_INPUT << 8),
+ PWM3 | (MAP_TO_PWM_INPUT << 8),
+ PWM4 | (MAP_TO_PWM_INPUT << 8),
+ PWM5 | (MAP_TO_PWM_INPUT << 8),
+ PWM6 | (MAP_TO_PWM_INPUT << 8),
+ PWM7 | (MAP_TO_PWM_INPUT << 8),
+ PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
+ PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
+ PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
+ PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
+ PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
+ 0xFFFF
+};
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1
+ { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2
+ { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3
+ { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4
+ { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5
+ { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6
+ { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7
+ { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8
+ { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1
+ { TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2
+ { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // PWM11 - OUT3
+ { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD }, // PWM12 - OUT4
+ { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD }, // PWM13 - OUT5
+ { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD } // PWM14 - OUT6
+};
+
diff --git a/src/main/target/ALIENFLIGHTF1/target.h b/src/main/target/ALIENFLIGHTF1/target.h
new file mode 100644
index 0000000000..41adcaf6f8
--- /dev/null
+++ b/src/main/target/ALIENFLIGHTF1/target.h
@@ -0,0 +1,172 @@
+/*
+ * 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 "AFF1" // AlienFlight F1.
+
+#define LED0 PB3
+#define LED1 PB4
+
+#define BEEPER PA12
+
+#define BARO_XCLR_PIN PC13
+#define BARO_EOC_PIN PC14
+
+#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
+#define INVERTER_USART USART2
+
+#define USE_EXTI
+#define MAG_INT_EXTI PC14
+#define EXTI_CALLBACK_HANDLER_COUNT 3 // MPU data ready, MAG data ready, BMP085 EOC
+//#define DEBUG_MPU_DATA_READY_INTERRUPT
+#define USE_MPU_DATA_READY_SIGNAL
+//#define DEBUG_MAG_DATA_READY_INTERRUPT
+#define USE_MAG_DATA_READY_SIGNAL
+
+// SPI2
+// PB15 28 SPI2_MOSI
+// PB14 27 SPI2_MISO
+// PB13 26 SPI2_SCK
+// PB12 25 SPI2_NSS
+
+#define USE_SPI
+#define USE_SPI_DEVICE_2
+
+#define NAZE_SPI_INSTANCE SPI2
+#define NAZE_SPI_CS_GPIO GPIOB
+#define NAZE_SPI_CS_PIN PB12
+#define NAZE_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB
+
+// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision:
+#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO
+#define M25P16_CS_PIN NAZE_SPI_CS_PIN
+#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE
+
+#define MPU6500_CS_GPIO_CLK_PERIPHERAL NAZE_CS_GPIO_CLK_PERIPHERAL
+#define MPU6500_CS_GPIO NAZE_SPI_CS_GPIO
+#define MPU6500_CS_PIN NAZE_SPI_CS_PIN
+#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE
+
+#define USE_FLASHFS
+#define USE_FLASH_M25P16
+
+#define GYRO
+#define USE_GYRO_MPU3050
+#define USE_GYRO_MPU6050
+#define USE_GYRO_MPU6500
+#define USE_GYRO_SPI_MPU6500
+
+#define GYRO_MPU3050_ALIGN CW0_DEG
+#define GYRO_MPU6050_ALIGN CW0_DEG
+#define GYRO_MPU6500_ALIGN CW0_DEG
+
+#define ACC
+#define USE_ACC_ADXL345
+#define USE_ACC_BMA280
+#define USE_ACC_MMA8452
+#define USE_ACC_MPU6050
+#define USE_ACC_MPU6500
+#define USE_ACC_SPI_MPU6500
+
+#define ACC_ADXL345_ALIGN CW270_DEG
+#define ACC_MPU6050_ALIGN CW0_DEG
+#define ACC_MMA8452_ALIGN CW90_DEG
+#define ACC_BMA280_ALIGN CW0_DEG
+#define ACC_MPU6500_ALIGN CW0_DEG
+
+#define BARO
+#define USE_BARO_MS5611
+#define USE_BARO_BMP085
+#define USE_BARO_BMP280
+
+#define MAG
+#define USE_MAG_HMC5883
+#define MAG_HMC5883_ALIGN CW180_DEG
+
+#define SONAR
+#define SONAR_TRIGGER_PIN PB0
+#define SONAR_ECHO_PIN PB1
+#define SONAR_TRIGGER_PIN_PWM PB8
+#define SONAR_ECHO_PIN_PWM PB9
+
+#define DISPLAY
+
+#define USE_UART1
+#define USE_UART2
+#define USE_UART3
+#define USE_SOFTSERIAL1
+#define USE_SOFTSERIAL2
+#define SERIAL_PORT_COUNT 5
+
+#define SOFTSERIAL_1_TIMER TIM3
+#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
+#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6
+#define SOFTSERIAL_2_TIMER TIM3
+#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7
+#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
+
+// USART3 only on NAZE32_SP - Flex Port
+#define UART3_RX_PIN PB11
+#define UART3_TX_PIN PB10
+
+#define USE_I2C
+#define I2C_DEVICE (I2CDEV_2)
+
+// #define SOFT_I2C // enable to test software i2c
+// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
+// #define SOFT_I2C_PB67
+
+#define USE_ADC
+#define CURRENT_METER_ADC_PIN PB1
+#define VBAT_ADC_PIN PA4
+#define RSSI_ADC_PIN PA1
+#define EXTERNAL1_ADC_PIN PA5
+
+
+#define LED_STRIP
+#define WS2811_TIMER TIM3
+#define WS2811_PIN PA6
+#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
+#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
+
+#undef GPS
+
+#define SPEKTRUM_BIND
+// USART2, PA3
+#define BIND_PIN PA3
+
+// alternative defaults for AlienFlight F1 target
+#define TARGET_CONFIG
+
+#define BRUSHED_MOTORS
+#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
+#define SERIALRX_UART SERIAL_PORT_USART2
+
+#define HARDWARE_BIND_PLUG
+// Hardware bind plug at PB5 (Pin 41)
+#define BINDPLUG_PIN PB5
+
+
+// IO - assuming all IOs on 48pin package
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) )
+
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
diff --git a/src/main/target/ALIENFLIGHTF1/target.mk b/src/main/target/ALIENFLIGHTF1/target.mk
new file mode 100644
index 0000000000..07d81cf447
--- /dev/null
+++ b/src/main/target/ALIENFLIGHTF1/target.mk
@@ -0,0 +1,20 @@
+F1_TARGETS += $(TARGET)
+FEATURES = ONBOARDFLASH HIGHEND
+
+TARGET_SRC = \
+ drivers/accgyro_adxl345.c \
+ drivers/accgyro_bma280.c \
+ drivers/accgyro_l3g4200d.c \
+ drivers/accgyro_mma845x.c \
+ drivers/accgyro_mpu.c \
+ drivers/accgyro_mpu3050.c \
+ drivers/accgyro_mpu6050.c \
+ drivers/accgyro_mpu6500.c \
+ drivers/accgyro_spi_mpu6500.c \
+ drivers/barometer_bmp085.c \
+ drivers/barometer_bmp280.c \
+ drivers/barometer_ms5611.c \
+ drivers/compass_hmc5883l.c \
+ drivers/light_ws2811strip.c \
+ drivers/light_ws2811strip_stm32f10x.c \
+ drivers/sonar_hcsr04.c
diff --git a/src/main/target/NAZE/ALIENFLIGHTF1.mk b/src/main/target/NAZE/ALIENFLIGHTF1.mk
deleted file mode 100644
index e69de29bb2..0000000000
diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h
index 512746d003..0e8ba62be2 100644
--- a/src/main/target/NAZE/target.h
+++ b/src/main/target/NAZE/target.h
@@ -158,26 +158,6 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
-#ifdef ALIENFLIGHTF1
-// alternative defaults for AlienFlight F1 target
-#undef TARGET_BOARD_IDENTIFIER
-#define TARGET_BOARD_IDENTIFIER "AFF1" // AlienFlight F1.
-#define TARGET_CONFIG
-
-#undef BOARD_HAS_VOLTAGE_DIVIDER
-#undef USE_SERIAL_4WAY_BLHELI_INTERFACE
-
-#define BRUSHED_MOTORS
-#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
-#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
-#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
-#define SERIALRX_UART SERIAL_PORT_USART2
-
-#define HARDWARE_BIND_PLUG
-// Hardware bind plug at PB5 (Pin 41)
-#define BINDPLUG_PIN PB5
-#endif // ALIENFLIGHTF1
-
// IO - assuming all IOs on 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff