diff --git a/src/main/config/config.c b/src/main/config/config.c
index dcb0ce85c3..1af50acbc8 100755
--- a/src/main/config/config.c
+++ b/src/main/config/config.c
@@ -23,6 +23,7 @@
#include "debug.h"
#include "build_config.h"
+#include "debug.h"
#include "blackbox/blackbox_io.h"
diff --git a/src/main/drivers/accgyro_mma845x.c b/src/main/drivers/accgyro_mma845x.c
index 202b90e804..69a82a0adb 100644
--- a/src/main/drivers/accgyro_mma845x.c
+++ b/src/main/drivers/accgyro_mma845x.c
@@ -21,7 +21,7 @@
#include "platform.h"
#include "system.h"
-#include "gpio.h"
+#include "io.h"
#include "bus_i2c.h"
#include "sensor.h"
diff --git a/src/main/drivers/adc.c b/src/main/drivers/adc.c
index a65abf9128..6bba109396 100644
--- a/src/main/drivers/adc.c
+++ b/src/main/drivers/adc.c
@@ -27,6 +27,8 @@
#include "adc.h"
#include "adc_impl.h"
+#include "common/utils.h"
+
//#define DEBUG_ADC_CHANNELS
#ifdef USE_ADC
diff --git a/src/main/drivers/adc.h b/src/main/drivers/adc.h
index 55914a3365..47a4b52a0e 100644
--- a/src/main/drivers/adc.h
+++ b/src/main/drivers/adc.h
@@ -17,7 +17,7 @@
#pragma once
-#include "io.h"
+#include "io_types.h"
typedef enum {
ADC_BATTERY = 0,
diff --git a/src/main/drivers/adc_impl.h b/src/main/drivers/adc_impl.h
index 146ada62be..c89dc1bf53 100644
--- a/src/main/drivers/adc_impl.h
+++ b/src/main/drivers/adc_impl.h
@@ -17,8 +17,8 @@
#pragma once
-#include "io.h"
-#include "rcc.h"
+#include "io_types.h"
+#include "rcc_types.h"
#if defined(STM32F4)
#define ADC_TAG_MAP_COUNT 16
@@ -65,4 +65,4 @@ extern const adcTagMap_t adcTagMap[ADC_TAG_MAP_COUNT];
extern adc_config_t adcConfig[ADC_CHANNEL_COUNT];
extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
-uint8_t adcChannelByTag(ioTag_t ioTag);
\ No newline at end of file
+uint8_t adcChannelByTag(ioTag_t ioTag);
diff --git a/src/main/drivers/barometer_spi_bmp280.c b/src/main/drivers/barometer_spi_bmp280.c
index 9d97343e11..0c97684972 100644
--- a/src/main/drivers/barometer_spi_bmp280.c
+++ b/src/main/drivers/barometer_spi_bmp280.c
@@ -15,6 +15,7 @@
* along with Betaflight. If not, see .
*/
+#include
#include
#include
@@ -24,6 +25,7 @@
#include "barometer.h"
#include "barometer_bmp280.h"
+#include "io.h"
#ifdef USE_BARO_SPI_BMP280
#define DISABLE_BMP280 IOHi(bmp280CsPin)
diff --git a/src/main/drivers/bus_i2c.h b/src/main/drivers/bus_i2c.h
index 86f7a66181..26cce3792f 100644
--- a/src/main/drivers/bus_i2c.h
+++ b/src/main/drivers/bus_i2c.h
@@ -21,8 +21,8 @@
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
#define I2C_DEFAULT_TIMEOUT I2C_SHORT_TIMEOUT
-#include "drivers/io.h"
-#include "drivers/rcc.h"
+#include "io_types.h"
+#include "rcc_types.h"
#ifndef I2C_DEVICE
#define I2C_DEVICE I2CINVALID
diff --git a/src/main/drivers/bus_i2c_soft.c b/src/main/drivers/bus_i2c_soft.c
index 104c77c379..42ea8cadc9 100644
--- a/src/main/drivers/bus_i2c_soft.c
+++ b/src/main/drivers/bus_i2c_soft.c
@@ -22,7 +22,7 @@
#include "build_config.h"
#include "bus_i2c.h"
-#include "drivers/io.h"
+#include "io.h"
// Software I2C driver, using same pins as hardware I2C, with hw i2c module disabled.
// Can be configured for I2C2 pinout (SCL: PB10, SDA: PB11) or I2C1 pinout (SCL: PB6, SDA: PB7)
diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c
index 88b267f111..f8c5b23697 100644
--- a/src/main/drivers/bus_i2c_stm32f30x.c
+++ b/src/main/drivers/bus_i2c_stm32f30x.c
@@ -20,9 +20,10 @@
#include
-#include "gpio.h"
#include "system.h"
-#include "drivers/io_impl.h"
+#include "io.h"
+#include "io_impl.h"
+#include "rcc.h"
#include "bus_i2c.h"
diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h
index 5a6ea7dd37..58c76c9d78 100644
--- a/src/main/drivers/bus_spi.h
+++ b/src/main/drivers/bus_spi.h
@@ -17,9 +17,8 @@
#pragma once
-#include
-#include "io.h"
-#include "rcc.h"
+#include "io_types.h"
+#include "rcc_types.h"
#if defined(STM32F4) || defined(STM32F3)
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
diff --git a/src/main/drivers/compass_hmc5883l.h b/src/main/drivers/compass_hmc5883l.h
index 035a2c936f..e2f71fd28d 100644
--- a/src/main/drivers/compass_hmc5883l.h
+++ b/src/main/drivers/compass_hmc5883l.h
@@ -17,7 +17,7 @@
#pragma once
-#include "io.h"
+#include "io_types.h"
typedef struct hmc5883Config_s {
ioTag_t intTag;
diff --git a/src/main/drivers/dma.c b/src/main/drivers/dma.c
index 0ad411312e..7e4942fbe1 100644
--- a/src/main/drivers/dma.c
+++ b/src/main/drivers/dma.c
@@ -21,8 +21,8 @@
#include
-#include "drivers/nvic.h"
-#include "drivers/dma.h"
+#include "nvic.h"
+#include "dma.h"
/*
* DMA descriptors.
diff --git a/src/main/drivers/dma_stm32f4xx.c b/src/main/drivers/dma_stm32f4xx.c
index ec6e7908d3..8372ad0bcb 100644
--- a/src/main/drivers/dma_stm32f4xx.c
+++ b/src/main/drivers/dma_stm32f4xx.c
@@ -21,8 +21,8 @@
#include
-#include "drivers/nvic.h"
-#include "drivers/dma.h"
+#include "nvic.h"
+#include "dma.h"
/*
* DMA descriptors.
diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c
index a0afb64804..44d7b95464 100644
--- a/src/main/drivers/flash_m25p16.c
+++ b/src/main/drivers/flash_m25p16.c
@@ -22,9 +22,10 @@
#ifdef USE_FLASH_M25P16
-#include "drivers/flash_m25p16.h"
-#include "drivers/bus_spi.h"
-#include "drivers/system.h"
+#include "flash_m25p16.h"
+#include "io.h"
+#include "bus_spi.h"
+#include "system.h"
#define M25P16_INSTRUCTION_RDID 0x9F
#define M25P16_INSTRUCTION_READ_BYTES 0x03
diff --git a/src/main/drivers/flash_m25p16.h b/src/main/drivers/flash_m25p16.h
index 223efa1809..6cad8a8ea6 100644
--- a/src/main/drivers/flash_m25p16.h
+++ b/src/main/drivers/flash_m25p16.h
@@ -19,7 +19,7 @@
#include
#include "flash.h"
-#include "io.h"
+#include "io_types.h"
#define M25P16_PAGESIZE 256
diff --git a/src/main/drivers/gyro_sync.c b/src/main/drivers/gyro_sync.c
index cd95e186e1..dbdc2244c9 100644
--- a/src/main/drivers/gyro_sync.c
+++ b/src/main/drivers/gyro_sync.c
@@ -10,9 +10,9 @@
#include "platform.h"
-#include "drivers/sensor.h"
-#include "drivers/accgyro.h"
-#include "drivers/gyro_sync.h"
+#include "sensor.h"
+#include "accgyro.h"
+#include "gyro_sync.h"
static uint8_t mpuDividerDrops;
diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h
index d655646282..5afa4abb76 100644
--- a/src/main/drivers/io.h
+++ b/src/main/drivers/io.h
@@ -6,16 +6,7 @@
#include
#include "resource.h"
-// IO pin identification
-// make sure that ioTag_t can't be assigned into IO_t without warning
-typedef uint8_t ioTag_t; // packet tag to specify IO pin
-typedef void* IO_t; // type specifying IO pin. Currently ioRec_t pointer, but this may change
-
-// NONE initializer for ioTag_t variables
-#define IOTAG_NONE ((ioTag_t)0)
-
-// NONE initializer for IO_t variable
-#define IO_NONE ((IO_t)0)
+#include "io_types.h"
// preprocessor is used to convert pinid to requested C data value
// compile-time error is generated if requested pin is not available (not set in TARGET_IO_PORTx)
@@ -24,19 +15,6 @@ typedef void* IO_t; // type specifying IO pin. Currently ioRec_t poin
// expand pinid to to ioTag_t
#define IO_TAG(pinid) DEFIO_TAG(pinid)
-// both ioTag_t and IO_t are guarantied to be zero if pinid is NONE (no pin)
-// this simplifies initialization (globals are zeroed on start) and allows
-// omitting unused fields in structure initializers.
-// it is also possible to use IO_t and ioTag_t as boolean value
-// TODO - this may conflict with requirement to generate warning/error on IO_t - ioTag_t assignment
-// IO_t being pointer is only possibility I know of ..
-
-// pin config handling
-// pin config is packed into ioConfig_t to decrease memory requirements
-// IOCFG_x macros are defined for common combinations for all CPUs; this
-// helps masking CPU differences
-
-typedef uint8_t ioConfig_t; // packed IO configuration
#if defined(STM32F1)
// mode is using only bits 6-2
diff --git a/src/main/drivers/io_types.h b/src/main/drivers/io_types.h
new file mode 100644
index 0000000000..ba80cd3bc7
--- /dev/null
+++ b/src/main/drivers/io_types.h
@@ -0,0 +1,28 @@
+#pragma once
+
+#include
+
+// IO pin identification
+// make sure that ioTag_t can't be assigned into IO_t without warning
+typedef uint8_t ioTag_t; // packet tag to specify IO pin
+typedef void* IO_t; // type specifying IO pin. Currently ioRec_t pointer, but this may change
+
+// NONE initializer for ioTag_t variables
+#define IOTAG_NONE ((ioTag_t)0)
+
+// NONE initializer for IO_t variable
+#define IO_NONE ((IO_t)0)
+
+// both ioTag_t and IO_t are guarantied to be zero if pinid is NONE (no pin)
+// this simplifies initialization (globals are zeroed on start) and allows
+// omitting unused fields in structure initializers.
+// it is also possible to use IO_t and ioTag_t as boolean value
+// TODO - this may conflict with requirement to generate warning/error on IO_t - ioTag_t assignment
+// IO_t being pointer is only possibility I know of ..
+
+// pin config handling
+// pin config is packed into ioConfig_t to decrease memory requirements
+// IOCFG_x macros are defined for common combinations for all CPUs; this
+// helps masking CPU differences
+
+typedef uint8_t ioConfig_t; // packed IO configuration
diff --git a/src/main/drivers/light_ws2811strip.c b/src/main/drivers/light_ws2811strip.c
index 6c8f2bb18a..d9c29af370 100644
--- a/src/main/drivers/light_ws2811strip.c
+++ b/src/main/drivers/light_ws2811strip.c
@@ -36,8 +36,8 @@
#include "common/color.h"
#include "common/colorconversion.h"
-#include "drivers/dma.h"
-#include "drivers/light_ws2811strip.h"
+#include "dma.h"
+#include "light_ws2811strip.h"
uint8_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
volatile uint8_t ws2811LedDataTransferInProgress = 0;
diff --git a/src/main/drivers/light_ws2811strip_stm32f10x.c b/src/main/drivers/light_ws2811strip_stm32f10x.c
index 4b588a0c9f..911b7cdc66 100644
--- a/src/main/drivers/light_ws2811strip_stm32f10x.c
+++ b/src/main/drivers/light_ws2811strip_stm32f10x.c
@@ -23,10 +23,11 @@
#ifdef LED_STRIP
#include "common/color.h"
-#include "drivers/light_ws2811strip.h"
+#include "light_ws2811strip.h"
#include "nvic.h"
#include "io.h"
#include "dma.h"
+#include "rcc.h"
#include "timer.h"
static IO_t ws2811IO = IO_NONE;
diff --git a/src/main/drivers/light_ws2811strip_stm32f30x.c b/src/main/drivers/light_ws2811strip_stm32f30x.c
index 8379188f99..1fadfb1f03 100644
--- a/src/main/drivers/light_ws2811strip_stm32f30x.c
+++ b/src/main/drivers/light_ws2811strip_stm32f30x.c
@@ -26,7 +26,7 @@
#include "nvic.h"
#include "common/color.h"
-#include "drivers/light_ws2811strip.h"
+#include "light_ws2811strip.h"
#include "dma.h"
#include "rcc.h"
#include "timer.h"
diff --git a/src/main/drivers/max7456.c b/src/main/drivers/max7456.c
index 82f3f29af9..7ddc2a058b 100644
--- a/src/main/drivers/max7456.c
+++ b/src/main/drivers/max7456.c
@@ -19,16 +19,19 @@
#include
#include "platform.h"
-#include "version.h"
#ifdef USE_MAX7456
+#include "version.h"
+
#include "common/printf.h"
-#include "drivers/bus_spi.h"
-#include "drivers/light_led.h"
-#include "drivers/system.h"
-#include "drivers/nvic.h"
-#include "drivers/dma.h"
+
+#include "bus_spi.h"
+#include "light_led.h"
+#include "io.h"
+#include "system.h"
+#include "nvic.h"
+#include "dma.h"
#include "max7456.h"
#include "max7456_symbols.h"
diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h
index 29a5d02f15..c017061835 100644
--- a/src/main/drivers/pwm_mapping.h
+++ b/src/main/drivers/pwm_mapping.h
@@ -17,7 +17,7 @@
#pragma once
-#include "timer.h"
+#include "io_types.h"
#define MAX_PWM_MOTORS 12
#define MAX_PWM_SERVOS 8
@@ -88,10 +88,11 @@ typedef enum {
PWM_PF_OUTPUT_PROTOCOL_ONESHOT = (1 << 4)
} pwmPortFlags_e;
+struct timerHardware_s;
typedef struct pwmPortConfiguration_s {
uint8_t index;
pwmPortFlags_e flags;
- const timerHardware_t *timerHardware;
+ const struct timerHardware_s *timerHardware;
} pwmPortConfiguration_t;
typedef struct pwmOutputConfiguration_s {
diff --git a/src/main/drivers/pwm_rx.c b/src/main/drivers/pwm_rx.c
index 3c72d104dc..60af85e97b 100644
--- a/src/main/drivers/pwm_rx.c
+++ b/src/main/drivers/pwm_rx.c
@@ -30,7 +30,7 @@
#include "system.h"
#include "nvic.h"
-#include "gpio.h"
+#include "io.h"
#include "timer.h"
#include "pwm_output.h"
diff --git a/src/main/drivers/rcc.h b/src/main/drivers/rcc.h
index fb04ec7e2c..69dce965f9 100644
--- a/src/main/drivers/rcc.h
+++ b/src/main/drivers/rcc.h
@@ -2,6 +2,7 @@
#include "platform.h"
#include "common/utils.h"
+#include "rcc_types.h"
enum rcc_reg {
RCC_EMPTY = 0, // make sure that default value (0) does not enable anything
@@ -17,9 +18,6 @@ enum rcc_reg {
#define RCC_APB1(periph) RCC_ENCODE(RCC_APB1, RCC_APB1ENR_ ## periph ## EN)
#define RCC_AHB1(periph) RCC_ENCODE(RCC_AHB1, RCC_AHB1ENR_ ## periph ## EN)
-typedef uint8_t rccPeriphTag_t;
-
void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState);
void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState);
-
diff --git a/src/main/drivers/rcc_types.h b/src/main/drivers/rcc_types.h
new file mode 100644
index 0000000000..1b7d7b9f2f
--- /dev/null
+++ b/src/main/drivers/rcc_types.h
@@ -0,0 +1,4 @@
+#pragma once
+
+typedef uint8_t rccPeriphTag_t;
+
diff --git a/src/main/drivers/sdcard.c b/src/main/drivers/sdcard.c
index 878d5eacf6..a86fc74577 100644
--- a/src/main/drivers/sdcard.c
+++ b/src/main/drivers/sdcard.c
@@ -25,8 +25,8 @@
#include "nvic.h"
#include "io.h"
-#include "drivers/bus_spi.h"
-#include "drivers/system.h"
+#include "bus_spi.h"
+#include "system.h"
#include "sdcard.h"
#include "sdcard_standard.h"
diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c
index 2c2cebbac6..50c6055ddd 100644
--- a/src/main/drivers/serial_usb_vcp.c
+++ b/src/main/drivers/serial_usb_vcp.c
@@ -22,7 +22,7 @@
#include "build_config.h"
#include "common/utils.h"
-#include "drivers/io.h"
+#include "io.h"
#include "usb_core.h"
#ifdef STM32F4
@@ -32,7 +32,7 @@
#include "hw_config.h"
#endif
-#include "drivers/system.h"
+#include "system.h"
#include "serial.h"
#include "serial_usb_vcp.h"
diff --git a/src/main/drivers/sonar_hcsr04.h b/src/main/drivers/sonar_hcsr04.h
index d734f62f4f..cb3f38c989 100644
--- a/src/main/drivers/sonar_hcsr04.h
+++ b/src/main/drivers/sonar_hcsr04.h
@@ -17,8 +17,7 @@
#pragma once
-#include "platform.h"
-#include "io.h"
+#include "io_types.h"
typedef struct sonarHardware_s {
ioTag_t triggerTag;
diff --git a/src/main/drivers/sound_beeper.h b/src/main/drivers/sound_beeper.h
index ab7a7c3dfc..9caad4f554 100644
--- a/src/main/drivers/sound_beeper.h
+++ b/src/main/drivers/sound_beeper.h
@@ -17,7 +17,7 @@
#pragma once
-#include "drivers/io.h"
+#include "io_types.h"
#ifdef BEEPER
#define BEEP_TOGGLE systemBeepToggle()
diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c
index 15e36cce3f..5051588c99 100755
--- a/src/main/drivers/timer.c
+++ b/src/main/drivers/timer.c
@@ -25,7 +25,7 @@
#include "nvic.h"
-#include "gpio.h"
+#include "io.h"
#include "rcc.h"
#include "system.h"
diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h
index 7050bbabda..00410a9c68 100644
--- a/src/main/drivers/timer.h
+++ b/src/main/drivers/timer.h
@@ -17,12 +17,11 @@
#pragma once
-#include "io.h"
-#include "rcc.h"
+#include
+#include
-#if !defined(USABLE_TIMER_CHANNEL_COUNT)
-#define USABLE_TIMER_CHANNEL_COUNT 14
-#endif
+#include "io_types.h"
+#include "rcc_types.h"
typedef uint16_t captureCompare_t; // 16 bit on both 103 and 303, just register access must be 32bit sometimes (use timCCR_t)
diff --git a/src/main/drivers/timer_stm32f10x.c b/src/main/drivers/timer_stm32f10x.c
index 1a5085e63a..49106818f0 100644
--- a/src/main/drivers/timer_stm32f10x.c
+++ b/src/main/drivers/timer_stm32f10x.c
@@ -5,6 +5,11 @@
http://www.st.com/software_license_agreement_liberty_v2
*/
+#include
+#include
+
+#include "platform.h"
+
#include "stm32f10x.h"
#include "rcc.h"
#include "timer.h"
diff --git a/src/main/drivers/timer_stm32f30x.c b/src/main/drivers/timer_stm32f30x.c
index 04069b20c3..99111bad77 100644
--- a/src/main/drivers/timer_stm32f30x.c
+++ b/src/main/drivers/timer_stm32f30x.c
@@ -5,6 +5,11 @@
http://www.st.com/software_license_agreement_liberty_v2
*/
+#include
+#include
+
+#include "platform.h"
+
#include "stm32f30x.h"
#include "rcc.h"
#include "timer.h"
diff --git a/src/main/drivers/timer_stm32f4xx.c b/src/main/drivers/timer_stm32f4xx.c
index af09f85e1b..ccce10350a 100644
--- a/src/main/drivers/timer_stm32f4xx.c
+++ b/src/main/drivers/timer_stm32f4xx.c
@@ -5,9 +5,14 @@
http://www.st.com/software_license_agreement_liberty_v2
*/
+#include
+#include
+
+#include "platform.h"
+
#include "stm32f4xx.h"
-#include "timer.h"
#include "rcc.h"
+#include "timer.h"
/**
* @brief Selects the TIM Output Compare Mode.
diff --git a/src/main/drivers/transponder_ir.c b/src/main/drivers/transponder_ir.c
index 626c60097c..dbc6749af7 100644
--- a/src/main/drivers/transponder_ir.c
+++ b/src/main/drivers/transponder_ir.c
@@ -21,9 +21,9 @@
#include
-#include "drivers/dma.h"
-#include "drivers/nvic.h"
-#include "drivers/transponder_ir.h"
+#include "dma.h"
+#include "nvic.h"
+#include "transponder_ir.h"
/*
* Implementation note:
diff --git a/src/main/drivers/transponder_ir_stm32f30x.c b/src/main/drivers/transponder_ir_stm32f30x.c
index 3962e1c999..0bff2e112c 100644
--- a/src/main/drivers/transponder_ir_stm32f30x.c
+++ b/src/main/drivers/transponder_ir_stm32f30x.c
@@ -20,9 +20,9 @@
#include
-#include "drivers/gpio.h"
-#include "drivers/transponder_ir.h"
-#include "drivers/nvic.h"
+#include "gpio.h"
+#include "transponder_ir.h"
+#include "nvic.h"
#ifndef TRANSPONDER_GPIO
#define USE_TRANSPONDER_ON_DMA1_CHANNEL3
diff --git a/src/main/drivers/vtx_rtc6705.c b/src/main/drivers/vtx_rtc6705.c
index 93ffa83ecb..08ec758e8d 100644
--- a/src/main/drivers/vtx_rtc6705.c
+++ b/src/main/drivers/vtx_rtc6705.c
@@ -31,9 +31,9 @@
#include "common/maths.h"
-#include "drivers/vtx_rtc6705.h"
-#include "drivers/bus_spi.h"
-#include "drivers/system.h"
+#include "vtx_rtc6705.h"
+#include "bus_spi.h"
+#include "system.h"
#define RTC6705_SET_HEAD 0x3210 //fosc=8mhz r=400
#define RTC6705_SET_A1 0x8F3031 //5865
diff --git a/src/main/drivers/vtx_soft_spi_rtc6705.c b/src/main/drivers/vtx_soft_spi_rtc6705.c
index 4ceba50df9..e6340680fa 100644
--- a/src/main/drivers/vtx_soft_spi_rtc6705.c
+++ b/src/main/drivers/vtx_soft_spi_rtc6705.c
@@ -22,9 +22,10 @@
#ifdef USE_RTC6705
-#include "drivers/bus_spi.h"
-#include "drivers/system.h"
-#include "drivers/light_led.h"
+#include "bus_spi.h"
+#include "io.h"
+#include "system.h"
+#include "light_led.h"
#include "vtx_soft_spi_rtc6705.h"
diff --git a/src/main/io/serial_4way_avrootloader.c b/src/main/io/serial_4way_avrootloader.c
index f0f5525813..223d3e10cd 100644
--- a/src/main/io/serial_4way_avrootloader.c
+++ b/src/main/io/serial_4way_avrootloader.c
@@ -25,8 +25,10 @@
#include "platform.h"
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
+#include "drivers/io_types.h"
#include "drivers/system.h"
#include "drivers/serial.h"
+#include "drivers/timer.h"
#include "drivers/pwm_mapping.h"
#include "io/serial.h"
#include "io/serial_msp.h"
diff --git a/src/main/main.c b/src/main/main.c
index 24b983308d..436f5b5798 100644
--- a/src/main/main.c
+++ b/src/main/main.c
@@ -33,6 +33,7 @@
#include "drivers/system.h"
#include "drivers/dma.h"
#include "drivers/gpio.h"
+#include "drivers/io.h"
#include "drivers/light_led.h"
#include "drivers/sound_beeper.h"
#include "drivers/timer.h"
diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c
index bb46059ac1..c3465b3934 100755
--- a/src/main/sensors/initialisation.c
+++ b/src/main/sensors/initialisation.c
@@ -24,7 +24,7 @@
#include "common/axis.h"
-#include "drivers/gpio.h"
+#include "drivers/io.h"
#include "drivers/system.h"
#include "drivers/exti.h"
diff --git a/src/main/target/AIORACERF3/target.c b/src/main/target/AIORACERF3/target.c
index e780364ec2..f950c67844 100644
--- a/src/main/target/AIORACERF3/target.c
+++ b/src/main/target/AIORACERF3/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/AIR32/target.c b/src/main/target/AIR32/target.c
index 378627daaf..b5b9889379 100644
--- a/src/main/target/AIR32/target.c
+++ b/src/main/target/AIR32/target.c
@@ -20,6 +20,7 @@
#include
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
+#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM9 | (MAP_TO_PPM_INPUT << 8), // PPM input
diff --git a/src/main/target/ALIENFLIGHTF1/target.c b/src/main/target/ALIENFLIGHTF1/target.c
index 7116b53551..dec8739ba0 100644
--- a/src/main/target/ALIENFLIGHTF1/target.c
+++ b/src/main/target/ALIENFLIGHTF1/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/ALIENFLIGHTF1/target.h b/src/main/target/ALIENFLIGHTF1/target.h
index 6d945008f7..04984912cd 100644
--- a/src/main/target/ALIENFLIGHTF1/target.h
+++ b/src/main/target/ALIENFLIGHTF1/target.h
@@ -90,4 +90,5 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) )
+#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
diff --git a/src/main/target/ALIENFLIGHTF3/target.c b/src/main/target/ALIENFLIGHTF3/target.c
index c1946aa17c..8169e9e912 100644
--- a/src/main/target/ALIENFLIGHTF3/target.c
+++ b/src/main/target/ALIENFLIGHTF3/target.c
@@ -20,6 +20,7 @@
#include
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
+#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM11 | (MAP_TO_PPM_INPUT << 8), // PPM input
diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h
index 28a896ff01..d2e9e92ba4 100644
--- a/src/main/target/ALIENFLIGHTF3/target.h
+++ b/src/main/target/ALIENFLIGHTF3/target.h
@@ -35,8 +35,6 @@
#define BEEPER PA5
-#define USABLE_TIMER_CHANNEL_COUNT 11
-
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define USE_EXTI
@@ -131,5 +129,6 @@
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
+#define USABLE_TIMER_CHANNEL_COUNT 11
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17) )
diff --git a/src/main/target/ALIENFLIGHTF4/target.c b/src/main/target/ALIENFLIGHTF4/target.c
index efedb56689..dafcdf86da 100644
--- a/src/main/target/ALIENFLIGHTF4/target.c
+++ b/src/main/target/ALIENFLIGHTF4/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/BLUEJAYF4/target.c b/src/main/target/BLUEJAYF4/target.c
index b85e50f539..83e0700cd5 100644
--- a/src/main/target/BLUEJAYF4/target.c
+++ b/src/main/target/BLUEJAYF4/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/CC3D/target.c b/src/main/target/CC3D/target.c
index a870de9e24..589c6af30d 100644
--- a/src/main/target/CC3D/target.c
+++ b/src/main/target/CC3D/target.c
@@ -20,6 +20,7 @@
#include
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
+#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
diff --git a/src/main/target/CHEBUZZF3/target.c b/src/main/target/CHEBUZZF3/target.c
index 631d83e6aa..c2aca46716 100644
--- a/src/main/target/CHEBUZZF3/target.c
+++ b/src/main/target/CHEBUZZF3/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/CJMCU/target.c b/src/main/target/CJMCU/target.c
index 0f8228559e..3562e3234d 100644
--- a/src/main/target/CJMCU/target.c
+++ b/src/main/target/CJMCU/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/CJMCU/target.h b/src/main/target/CJMCU/target.h
index 973e0984f9..beb4be9657 100644
--- a/src/main/target/CJMCU/target.h
+++ b/src/main/target/CJMCU/target.h
@@ -71,4 +71,5 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
+#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
diff --git a/src/main/target/COLIBRI_RACE/target.c b/src/main/target/COLIBRI_RACE/target.c
index 91b21c8b36..099f9b62e7 100644
--- a/src/main/target/COLIBRI_RACE/target.c
+++ b/src/main/target/COLIBRI_RACE/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/DOGE/target.c b/src/main/target/DOGE/target.c
index 05b642f088..ca13ef7d0b 100644
--- a/src/main/target/DOGE/target.c
+++ b/src/main/target/DOGE/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h
index 2399ede8d1..3f40c4ab43 100644
--- a/src/main/target/DOGE/target.h
+++ b/src/main/target/DOGE/target.h
@@ -67,11 +67,6 @@
#define M25P16_CS_PIN PC15
#define M25P16_SPI_INSTANCE SPI2
-// timer definitions in drivers/timer.c
-// channel mapping in drivers/pwm_mapping.c
-// only 6 outputs available on hardware
-#define USABLE_TIMER_CHANNEL_COUNT 9
-
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
@@ -147,5 +142,9 @@
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
+// timer definitions in drivers/timer.c
+// channel mapping in drivers/pwm_mapping.c
+// only 6 outputs available on hardware
+#define USABLE_TIMER_CHANNEL_COUNT 9
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15))
diff --git a/src/main/target/EUSTM32F103RC/target.c b/src/main/target/EUSTM32F103RC/target.c
index b2a0db9a16..0dc2d66044 100644
--- a/src/main/target/EUSTM32F103RC/target.c
+++ b/src/main/target/EUSTM32F103RC/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/EUSTM32F103RC/target.h b/src/main/target/EUSTM32F103RC/target.h
index 12ec85f371..d883641d4f 100644
--- a/src/main/target/EUSTM32F103RC/target.h
+++ b/src/main/target/EUSTM32F103RC/target.h
@@ -113,5 +113,6 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
+#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
diff --git a/src/main/target/F4BY/target.c b/src/main/target/F4BY/target.c
index a8d80e823d..e9befde0ab 100644
--- a/src/main/target/F4BY/target.c
+++ b/src/main/target/F4BY/target.c
@@ -3,17 +3,18 @@
#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
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),
+ 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),
- PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
- PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
+ PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
+ PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM7 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM6 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
@@ -47,13 +48,13 @@ const uint16_t multiPWM[] = {
const uint16_t airPPM[] = {
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_SERVO_OUTPUT << 8),
+ PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
+ PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
- PWM15 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
- PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
+ PWM15 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
+ PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM7 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM6 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
@@ -84,23 +85,23 @@ const uint16_t airPWM[] = {
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
- { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S1_IN
- { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S2_IN
- { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S3_IN
- { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S4_IN
- { TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S5_IN
- { TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S6_IN
- { TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S7_IN
- { TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S8_IN
+ { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S1_IN
+ { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S2_IN
+ { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S3_IN
+ { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S4_IN
+ { TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S5_IN
+ { TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S6_IN
+ { TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S7_IN
+ { TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S8_IN
- { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2}, // S1_OUT
- { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2}, // S2_OUT
- { TIM5, IO_TAG(PA2), TIM_Channel_3, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5}, // S3_OUT
- { TIM5, IO_TAG(PA3), TIM_Channel_4, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5}, // S4_OUT
- { TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S5_OUT
- { TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S6_OUT
- { TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S7_OUT
- { TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S8_OUT
+ { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2}, // S1_OUT
+ { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2}, // S2_OUT
+ { TIM5, IO_TAG(PA2), TIM_Channel_3, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5}, // S3_OUT
+ { TIM5, IO_TAG(PA3), TIM_Channel_4, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5}, // S4_OUT
+ { TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S5_OUT
+ { TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S6_OUT
+ { TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S7_OUT
+ { TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S8_OUT
{ TIM9, IO_TAG(PE6), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // sonar echo if needed
};
diff --git a/src/main/target/F4BY/target.h b/src/main/target/F4BY/target.h
index 7c9e89b48b..d8f8154031 100644
--- a/src/main/target/F4BY/target.h
+++ b/src/main/target/F4BY/target.h
@@ -74,8 +74,6 @@
#define SDCARD_DMA_CHANNEL DMA_Channel_0
-#define USABLE_TIMER_CHANNEL_COUNT 17
-
#define USE_VCP
#define VBUS_SENSING_PIN PA9
@@ -156,5 +154,6 @@
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff
+#define USABLE_TIMER_CHANNEL_COUNT 17
#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9))
diff --git a/src/main/target/FURYF3/target.c b/src/main/target/FURYF3/target.c
index bf4ff7b20a..db28609d97 100644
--- a/src/main/target/FURYF3/target.c
+++ b/src/main/target/FURYF3/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/FURYF4/target.c b/src/main/target/FURYF4/target.c
index ac600ea439..a53aa4d447 100644
--- a/src/main/target/FURYF4/target.c
+++ b/src/main/target/FURYF4/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/FURYF4/target.h b/src/main/target/FURYF4/target.h
index 8f69378592..05ff286283 100644
--- a/src/main/target/FURYF4/target.h
+++ b/src/main/target/FURYF4/target.h
@@ -101,8 +101,6 @@
#define M25P16_CS_PIN PB3
#define M25P16_SPI_INSTANCE SPI3
-#define USABLE_TIMER_CHANNEL_COUNT 5
-
#define USE_VCP
#define VBUS_SENSING_PIN PC5
#define VBUS_SENSING_ENABLED
@@ -167,5 +165,6 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
+#define USABLE_TIMER_CHANNEL_COUNT 5
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(9))
diff --git a/src/main/target/IRCFUSIONF3/target.c b/src/main/target/IRCFUSIONF3/target.c
index dd87a86410..2e4e12fb0a 100644
--- a/src/main/target/IRCFUSIONF3/target.c
+++ b/src/main/target/IRCFUSIONF3/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/IRCFUSIONF3/target.h b/src/main/target/IRCFUSIONF3/target.h
index 8dbd6e55ba..9ceabb35d2 100644
--- a/src/main/target/IRCFUSIONF3/target.h
+++ b/src/main/target/IRCFUSIONF3/target.h
@@ -23,8 +23,6 @@
#define LED0 PB3
-#define USABLE_TIMER_CHANNEL_COUNT 17
-
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready, no MAG
#define USE_MPU_DATA_READY_SIGNAL
@@ -105,5 +103,6 @@
#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 17
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))
diff --git a/src/main/target/KISSFC/target.c b/src/main/target/KISSFC/target.c
index cbb9d74818..a443fe862f 100644
--- a/src/main/target/KISSFC/target.c
+++ b/src/main/target/KISSFC/target.c
@@ -20,6 +20,7 @@
#include
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
+#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM7 | (MAP_TO_PPM_INPUT << 8),
diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h
index 05346145d6..e532b9d782 100644
--- a/src/main/target/KISSFC/target.h
+++ b/src/main/target/KISSFC/target.h
@@ -28,8 +28,6 @@
#define BEEPER PB13
#define BEEPER_INVERTED
-#define USABLE_TIMER_CHANNEL_COUNT 12
-
#define USE_EXTI
#define MPU_INT_EXTI PB2
#define USE_MPU_DATA_READY_SIGNAL
@@ -84,4 +82,5 @@
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTF (BIT(4))
+#define USABLE_TIMER_CHANNEL_COUNT 12
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17))
diff --git a/src/main/target/LUX_RACE/target.c b/src/main/target/LUX_RACE/target.c
index 91b21c8b36..099f9b62e7 100644
--- a/src/main/target/LUX_RACE/target.c
+++ b/src/main/target/LUX_RACE/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/MICROSCISKY/target.c b/src/main/target/MICROSCISKY/target.c
index 7116b53551..dec8739ba0 100644
--- a/src/main/target/MICROSCISKY/target.c
+++ b/src/main/target/MICROSCISKY/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/MICROSCISKY/target.h b/src/main/target/MICROSCISKY/target.h
index 80d4f04856..9138f74e86 100644
--- a/src/main/target/MICROSCISKY/target.h
+++ b/src/main/target/MICROSCISKY/target.h
@@ -97,4 +97,5 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) )
+#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
diff --git a/src/main/target/MOTOLAB/target.c b/src/main/target/MOTOLAB/target.c
index a89063cc9a..cc898ba834 100644
--- a/src/main/target/MOTOLAB/target.c
+++ b/src/main/target/MOTOLAB/target.c
@@ -20,6 +20,7 @@
#include
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
+#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM9 | (MAP_TO_PPM_INPUT << 8), // PPM input
diff --git a/src/main/target/NAZE/target.c b/src/main/target/NAZE/target.c
index 7116b53551..dec8739ba0 100644
--- a/src/main/target/NAZE/target.c
+++ b/src/main/target/NAZE/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h
index 0e8ba62be2..7e3705b47a 100644
--- a/src/main/target/NAZE/target.h
+++ b/src/main/target/NAZE/target.h
@@ -163,4 +163,5 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) )
+#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
diff --git a/src/main/target/OLIMEXINO/target.c b/src/main/target/OLIMEXINO/target.c
index ea20267b3c..5d0a271c5b 100644
--- a/src/main/target/OLIMEXINO/target.c
+++ b/src/main/target/OLIMEXINO/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/OLIMEXINO/target.h b/src/main/target/OLIMEXINO/target.h
index bb270cb4fc..ae8ac3b38e 100644
--- a/src/main/target/OLIMEXINO/target.h
+++ b/src/main/target/OLIMEXINO/target.h
@@ -91,4 +91,5 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
+#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
diff --git a/src/main/target/OMNIBUS/target.c b/src/main/target/OMNIBUS/target.c
index 977d623f85..a3cd3e54d3 100644
--- a/src/main/target/OMNIBUS/target.c
+++ b/src/main/target/OMNIBUS/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/OMNIBUSF4/target.c b/src/main/target/OMNIBUSF4/target.c
index 7dd021055e..2ed3eab8fb 100644
--- a/src/main/target/OMNIBUSF4/target.c
+++ b/src/main/target/OMNIBUSF4/target.c
@@ -20,6 +20,7 @@
#include
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
+#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
diff --git a/src/main/target/PIKOBLX/target.c b/src/main/target/PIKOBLX/target.c
index a89063cc9a..cc898ba834 100644
--- a/src/main/target/PIKOBLX/target.c
+++ b/src/main/target/PIKOBLX/target.c
@@ -20,6 +20,7 @@
#include
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
+#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM9 | (MAP_TO_PPM_INPUT << 8), // PPM input
diff --git a/src/main/target/PIKOBLX/target.h b/src/main/target/PIKOBLX/target.h
index 111f6fc476..7a104b7466 100644
--- a/src/main/target/PIKOBLX/target.h
+++ b/src/main/target/PIKOBLX/target.h
@@ -28,8 +28,6 @@
#define BEEPER PA0
#define BEEPER_INVERTED
-#define USABLE_TIMER_CHANNEL_COUNT 9
-
// MPU6000 interrupts
#define USE_EXTI
#define MPU_INT_EXTI PA15
@@ -136,5 +134,6 @@
// !!TODO - check the following line is correct
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
+#define USABLE_TIMER_CHANNEL_COUNT 9
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))
diff --git a/src/main/target/PORT103R/target.c b/src/main/target/PORT103R/target.c
index 8f21b7cbb7..093fa6ee27 100644
--- a/src/main/target/PORT103R/target.c
+++ b/src/main/target/PORT103R/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/PORT103R/target.h b/src/main/target/PORT103R/target.h
index 66e83fa3d5..9f0239d572 100644
--- a/src/main/target/PORT103R/target.h
+++ b/src/main/target/PORT103R/target.h
@@ -123,5 +123,6 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
+#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
diff --git a/src/main/target/REVO/target.c b/src/main/target/REVO/target.c
index 67f7327285..a253a0b31f 100644
--- a/src/main/target/REVO/target.c
+++ b/src/main/target/REVO/target.c
@@ -20,6 +20,7 @@
#include
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
+#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
diff --git a/src/main/target/REVONANO/target.c b/src/main/target/REVONANO/target.c
index 9a579f2bc9..bf5023fc24 100644
--- a/src/main/target/REVONANO/target.c
+++ b/src/main/target/REVONANO/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/RMDO/target.c b/src/main/target/RMDO/target.c
index ee96272c11..d344cda357 100644
--- a/src/main/target/RMDO/target.c
+++ b/src/main/target/RMDO/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/SINGULARITY/target.c b/src/main/target/SINGULARITY/target.c
index 8131579519..e48d0c33b4 100644
--- a/src/main/target/SINGULARITY/target.c
+++ b/src/main/target/SINGULARITY/target.c
@@ -20,6 +20,7 @@
#include
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
+#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8),
diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h
index 09a5678174..ed23489a3a 100644
--- a/src/main/target/SINGULARITY/target.h
+++ b/src/main/target/SINGULARITY/target.h
@@ -25,8 +25,6 @@
#define BEEPER PC15
-#define USABLE_TIMER_CHANNEL_COUNT 10
-
#define USE_EXTI
#define MPU_INT_EXTI PC13
#define USE_MPU_DATA_READY_SIGNAL
@@ -115,5 +113,6 @@
// !!TODO - check the following line is correct
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
+#define USABLE_TIMER_CHANNEL_COUNT 10
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(16) |TIM_N(17))
diff --git a/src/main/target/SIRINFPV/target.c b/src/main/target/SIRINFPV/target.c
index b52fbd00e4..7d602c74b1 100644
--- a/src/main/target/SIRINFPV/target.c
+++ b/src/main/target/SIRINFPV/target.c
@@ -20,6 +20,7 @@
#include
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
+#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM7 | (MAP_TO_PPM_INPUT << 8),
diff --git a/src/main/target/SPARKY/target.c b/src/main/target/SPARKY/target.c
index 389617278b..20b1f185d3 100644
--- a/src/main/target/SPARKY/target.c
+++ b/src/main/target/SPARKY/target.c
@@ -20,6 +20,7 @@
#include
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
+#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM11 | (MAP_TO_PPM_INPUT << 8), // PPM input
diff --git a/src/main/target/SPRACINGF3/target.c b/src/main/target/SPRACINGF3/target.c
index ec9176a27f..99f79ec9b7 100644
--- a/src/main/target/SPRACINGF3/target.c
+++ b/src/main/target/SPRACINGF3/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/SPRACINGF3EVO/target.c b/src/main/target/SPRACINGF3EVO/target.c
index 843ad3d9aa..87eb5db35f 100644
--- a/src/main/target/SPRACINGF3EVO/target.c
+++ b/src/main/target/SPRACINGF3EVO/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/SPRACINGF3MINI/target.c b/src/main/target/SPRACINGF3MINI/target.c
index d1e3a0d8b2..bf8776aa92 100644
--- a/src/main/target/SPRACINGF3MINI/target.c
+++ b/src/main/target/SPRACINGF3MINI/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/STM32F3DISCOVERY/target.c b/src/main/target/STM32F3DISCOVERY/target.c
index 1712bebae2..d2c17db5a2 100644
--- a/src/main/target/STM32F3DISCOVERY/target.c
+++ b/src/main/target/STM32F3DISCOVERY/target.c
@@ -20,6 +20,7 @@
#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
diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h
index 592833bc48..a75e952171 100644
--- a/src/main/target/STM32F3DISCOVERY/target.h
+++ b/src/main/target/STM32F3DISCOVERY/target.h
@@ -165,5 +165,6 @@
#define TARGET_IO_PORTE 0xffff
#define TARGET_IO_PORTF 0x00ff
+#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(16) | TIM_N(17))
diff --git a/src/main/target/X_RACERSPI/target.c b/src/main/target/X_RACERSPI/target.c
index 85db79093c..a63258100e 100644
--- a/src/main/target/X_RACERSPI/target.c
+++ b/src/main/target/X_RACERSPI/target.c
@@ -5,6 +5,7 @@
#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
diff --git a/src/main/target/X_RACERSPI/target.h b/src/main/target/X_RACERSPI/target.h
index 7838b1f460..9cc822ebee 100644
--- a/src/main/target/X_RACERSPI/target.h
+++ b/src/main/target/X_RACERSPI/target.h
@@ -26,8 +26,6 @@
#define BEEPER PC15
#define BEEPER_INVERTED
-#define USABLE_TIMER_CHANNEL_COUNT 17
-
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH
@@ -128,5 +126,6 @@
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
+#define USABLE_TIMER_CHANNEL_COUNT 17
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
diff --git a/src/main/target/ZCOREF3/target.c b/src/main/target/ZCOREF3/target.c
index b72400e6fd..48a6ce60da 100644
--- a/src/main/target/ZCOREF3/target.c
+++ b/src/main/target/ZCOREF3/target.c
@@ -5,6 +5,7 @@
#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
diff --git a/src/main/target/ZCOREF3/target.h b/src/main/target/ZCOREF3/target.h
index c65abb7d92..5c07c78190 100644
--- a/src/main/target/ZCOREF3/target.h
+++ b/src/main/target/ZCOREF3/target.h
@@ -101,6 +101,5 @@
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 17 // PPM, 8 PWM, UART3 RX/TX, LED Strip
-
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
diff --git a/src/main/telemetry/frsky.c b/src/main/telemetry/frsky.c
index 33bd13193c..d698b958a0 100644
--- a/src/main/telemetry/frsky.c
+++ b/src/main/telemetry/frsky.c
@@ -19,6 +19,8 @@
* Initial FrSky Telemetry implementation by silpstream @ rcgroups.
* Addition protocol work by airmamaf @ github.
*/
+
+#include
#include
#include
diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c
index 96e2193e9a..6373d166eb 100644
--- a/src/main/telemetry/telemetry.c
+++ b/src/main/telemetry/telemetry.c
@@ -15,6 +15,7 @@
* along with Cleanflight. If not, see .
*/
+#include
#include
#include
@@ -22,7 +23,6 @@
#ifdef TELEMETRY
-#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/serial.h"
#include "drivers/serial_softserial.h"