diff --git a/Makefile b/Makefile
index ce527d4adc..f0a3ba2eb8 100644
--- a/Makefile
+++ b/Makefile
@@ -503,6 +503,7 @@ COMMON_SRC = \
drivers/rx_nrf24l01.c \
drivers/rx_spi.c \
drivers/rx_xn297.c \
+ drivers/pwm_esc_detect.c \
drivers/pwm_output.c \
drivers/pwm_rx.c \
drivers/rcc.c \
diff --git a/src/main/drivers/pwm_esc_detect.c b/src/main/drivers/pwm_esc_detect.c
new file mode 100644
index 0000000000..012f912688
--- /dev/null
+++ b/src/main/drivers/pwm_esc_detect.c
@@ -0,0 +1,55 @@
+/*
+ * 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
+
+#include "platform.h"
+
+#include "build/build_config.h"
+
+#include "system.h"
+#include "io.h"
+#include "pwm_esc_detect.h"
+#include "timer.h"
+
+#ifdef BRUSHED_ESC_AUTODETECT
+uint8_t hardwareMotorType = MOTOR_UNKNOWN;
+
+void detectBrushedESC(void)
+{
+ int i = 0;
+ while (!(timerHardware[i].usageFlags & TIM_USE_MOTOR) && (i < USABLE_TIMER_CHANNEL_COUNT)) {
+ i++;
+ }
+
+ IO_t MotorDetectPin = IOGetByTag(timerHardware[i].tag);
+ IOInit(MotorDetectPin, OWNER_SYSTEM, 0);
+ IOConfigGPIO(MotorDetectPin, IOCFG_IPU);
+
+ delayMicroseconds(10); // allow configuration to settle
+
+ // Check presence of brushed ESC's
+ if (IORead(MotorDetectPin)) {
+ hardwareMotorType = MOTOR_BRUSHLESS;
+ } else {
+ hardwareMotorType = MOTOR_BRUSHED;
+ }
+}
+#endif
diff --git a/src/main/drivers/pwm_esc_detect.h b/src/main/drivers/pwm_esc_detect.h
new file mode 100644
index 0000000000..b61dc0459a
--- /dev/null
+++ b/src/main/drivers/pwm_esc_detect.h
@@ -0,0 +1,29 @@
+/*
+ * 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
+
+#ifdef BRUSHED_ESC_AUTODETECT
+typedef enum {
+ MOTOR_UNKNOWN = 0,
+ MOTOR_BRUSHED,
+ MOTOR_BRUSHLESS
+} HardwareMotorTypes_e;
+
+extern uint8_t hardwareMotorType;
+
+void detectBrushedESC(void);
+#endif
diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c
index 90ad21c900..ed58b25291 100644
--- a/src/main/drivers/pwm_output.c
+++ b/src/main/drivers/pwm_output.c
@@ -24,7 +24,6 @@
#include "io.h"
#include "timer.h"
#include "pwm_output.h"
-#include "system.h"
#define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5)
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f)
@@ -281,28 +280,3 @@ void servoInit(const servoConfig_t *servoConfig)
}
#endif
-
-#ifdef BRUSHED_ESC_AUTODETECT
-uint8_t hardwareMotorType = MOTOR_UNKNOWN;
-
-void detectBrushedESC(void)
-{
- int i = 0;
- while (!(timerHardware[i].usageFlags & TIM_USE_MOTOR) && (i < USABLE_TIMER_CHANNEL_COUNT)) {
- i++;
- }
-
- IO_t MotorDetectPin = IOGetByTag(timerHardware[i].tag);
- IOInit(MotorDetectPin, OWNER_SYSTEM, 0);
- IOConfigGPIO(MotorDetectPin, IOCFG_IPU);
-
- delayMicroseconds(10); // allow configuration to settle
-
- // Check presence of brushed ESC's
- if (IORead(MotorDetectPin)) {
- hardwareMotorType = MOTOR_BRUSHLESS;
- } else {
- hardwareMotorType = MOTOR_BRUSHED;
- }
-}
-#endif
diff --git a/src/main/drivers/pwm_output.h b/src/main/drivers/pwm_output.h
index 8c6488298e..9d94a1d074 100644
--- a/src/main/drivers/pwm_output.h
+++ b/src/main/drivers/pwm_output.h
@@ -114,15 +114,3 @@ pwmOutputPort_t *pwmGetMotors(void);
bool pwmIsSynced(void);
void pwmDisableMotors(void);
void pwmEnableMotors(void);
-
-#ifdef BRUSHED_ESC_AUTODETECT
-typedef enum {
- MOTOR_UNKNOWN = 0,
- MOTOR_BRUSHED,
- MOTOR_BRUSHLESS
-} HardwareMotorTypes_e;
-
-extern uint8_t hardwareMotorType;
-
-void detectBrushedESC(void);
-#endif
diff --git a/src/main/fc/config.c b/src/main/fc/config.c
index 4359fcd2b4..3cf08b05a7 100755
--- a/src/main/fc/config.c
+++ b/src/main/fc/config.c
@@ -41,6 +41,7 @@
#include "drivers/pwm_rx.h"
#include "drivers/rx_spi.h"
#include "drivers/serial.h"
+#include "drivers/pwm_esc_detect.h"
#include "drivers/pwm_output.h"
#include "drivers/vcd.h"
#include "drivers/max7456.h"
diff --git a/src/main/main.c b/src/main/main.c
index 2bf3e063ae..f979db9d6c 100644
--- a/src/main/main.c
+++ b/src/main/main.c
@@ -44,6 +44,7 @@
#include "drivers/serial_uart.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
+#include "drivers/pwm_esc_detect.h"
#include "drivers/pwm_rx.h"
#include "drivers/pwm_output.h"
#include "drivers/adc.h"
diff --git a/src/main/target/ALIENFLIGHTF1/config.c b/src/main/target/ALIENFLIGHTF1/config.c
index 89bf61ecbb..109d2ff41a 100644
--- a/src/main/target/ALIENFLIGHTF1/config.c
+++ b/src/main/target/ALIENFLIGHTF1/config.c
@@ -20,6 +20,7 @@
#include
+#include "drivers/pwm_esc_detect.h"
#include "drivers/pwm_output.h"
#include "fc/rc_controls.h"
diff --git a/src/main/target/ALIENFLIGHTF3/config.c b/src/main/target/ALIENFLIGHTF3/config.c
index c14ed47be5..2628ed2625 100644
--- a/src/main/target/ALIENFLIGHTF3/config.c
+++ b/src/main/target/ALIENFLIGHTF3/config.c
@@ -24,6 +24,7 @@
#include "drivers/sensor.h"
#include "drivers/compass.h"
+#include "drivers/pwm_esc_detect.h"
#include "drivers/pwm_output.h"
#include "fc/rc_controls.h"
diff --git a/src/main/target/ALIENFLIGHTF4/config.c b/src/main/target/ALIENFLIGHTF4/config.c
index 7a9b8bc54d..ad5c4baa3c 100644
--- a/src/main/target/ALIENFLIGHTF4/config.c
+++ b/src/main/target/ALIENFLIGHTF4/config.c
@@ -24,6 +24,7 @@
#include "drivers/sensor.h"
#include "drivers/compass.h"
+#include "drivers/pwm_esc_detect.h"
#include "drivers/pwm_output.h"
#include "drivers/serial.h"