diff --git a/src/main/drivers/adc_stm32f10x.c b/src/main/drivers/adc_stm32f10x.c
index 02623b0f65..7838ca8acb 100644
--- a/src/main/drivers/adc_stm32f10x.c
+++ b/src/main/drivers/adc_stm32f10x.c
@@ -118,7 +118,7 @@ void adcInit(drv_adc_config_t *init)
const adcDevice_t adc = adcHardware[device];
- for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
+ for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].tag)
continue;
@@ -133,7 +133,7 @@ void adcInit(drv_adc_config_t *init)
RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI)
RCC_ClockCmd(adc.rccADC, ENABLE);
- dmaInit(dmaGetIdentifier(adc.DMAy_Channelx), OWNER_ADC_BATT + i, 0);
+ dmaInit(dmaGetIdentifier(adc.DMAy_Channelx), OWNER_ADC, 0);
DMA_DeInit(adc.DMAy_Channelx);
DMA_InitTypeDef DMA_InitStructure;
diff --git a/src/main/drivers/adc_stm32f30x.c b/src/main/drivers/adc_stm32f30x.c
index 2f7ffcb164..4a17a3ab9d 100644
--- a/src/main/drivers/adc_stm32f30x.c
+++ b/src/main/drivers/adc_stm32f30x.c
@@ -158,7 +158,7 @@ void adcInit(drv_adc_config_t *init)
RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz
RCC_ClockCmd(adc.rccADC, ENABLE);
- dmaInit(dmaGetIdentifier(adc.DMAy_Channelx), OWNER_ADC_BATT + i, 0);
+ dmaInit(dmaGetIdentifier(adc.DMAy_Channelx), OWNER_ADC, 0);
DMA_DeInit(adc.DMAy_Channelx);
diff --git a/src/main/drivers/adc_stm32f4xx.c b/src/main/drivers/adc_stm32f4xx.c
index f70088b4f4..92b66648b1 100644
--- a/src/main/drivers/adc_stm32f4xx.c
+++ b/src/main/drivers/adc_stm32f4xx.c
@@ -143,7 +143,7 @@ void adcInit(drv_adc_config_t *init)
RCC_ClockCmd(adc.rccADC, ENABLE);
- dmaInit(dmaGetIdentifier(adc.DMAy_Streamx), OWNER_ADC_BATT + i, 0);
+ dmaInit(dmaGetIdentifier(adc.DMAy_Streamx), OWNER_ADC, 0);
DMA_DeInit(adc.DMAy_Streamx);
diff --git a/src/main/drivers/adc_stm32f7xx.c b/src/main/drivers/adc_stm32f7xx.c
index 459b6cb12b..4bfa1435b4 100644
--- a/src/main/drivers/adc_stm32f7xx.c
+++ b/src/main/drivers/adc_stm32f7xx.c
@@ -141,7 +141,7 @@ void adcInit(drv_adc_config_t *init)
RCC_ClockCmd(adc.rccADC, ENABLE);
- dmaInit(dmaGetIdentifier(adc.DMAy_Streamx), OWNER_ADC_BATT + i, 0);
+ dmaInit(dmaGetIdentifier(adc.DMAy_Streamx), OWNER_ADC, 0);
ADCHandle.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV8;
ADCHandle.Init.ContinuousConvMode = ENABLE;
diff --git a/src/main/drivers/resource.c b/src/main/drivers/resource.c
index 4db94f7b08..1b5eb25cb0 100644
--- a/src/main/drivers/resource.c
+++ b/src/main/drivers/resource.c
@@ -3,7 +3,7 @@
*
* 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
+ * 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,
@@ -12,24 +12,51 @@
* 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 .
+ * along with Cleanflight. If not,see .
*/
#include "resource.h"
const char * const ownerNames[OWNER_TOTAL_COUNT] = {
- "FREE", "PWM", "PPM", "MOTOR", "SERVO", "LED",
- "ADC", "ADC_BATT", "ADC_CURR", "ADC_EXT", "ADC_RSSI",
- "SERIAL_TX", "SERIAL_RX",
- "DEBUG", "TIMER",
- "SONAR_TRIGGER", "SONAR_ECHO",
- "SYSTEM",
- "SPI_SCK", "SPI_MISO", "SPI_MOSI",
- "I2C_SDA", "I2C_SCL",
- "SDCARD_CS", "FLASH_CS", "BARO_CS", "MPU_CS", "OSD_CS", "RX_SPI_CS", "SPI_CS",
- "MPU_EXTI", "BARO_EXTI",
- "USB", "USB_DETECT", "BEEPER", "OSD", "SDCARD_DETECT",
+ "FREE",
+ "PWM",
+ "PPM",
+ "MOTOR",
+ "SERVO",
+ "LED",
+ "ADC",
+ "ADC_BATT",
+ "ADC_CURR",
+ "ADC_EXT",
+ "ADC_RSSI",
+ "SERIAL_TX",
+ "SERIAL_RX",
+ "DEBUG",
+ "TIMER",
+ "SONAR_TRIGGER",
+ "SONAR_ECHO",
+ "SYSTEM",
+ "SPI_SCK",
+ "SPI_MISO",
+ "SPI_MOSI",
+ "I2C_SDA",
+ "I2C_SCL",
+ "SDCARD_CS",
+ "FLASH_CS",
+ "BARO_CS",
+ "MPU_CS",
+ "OSD_CS",
+ "RX_SPI_CS",
+ "SPI_CS",
+ "MPU_EXTI",
+ "BARO_EXTI",
+ "USB",
+ "USB_DETECT",
+ "BEEPER",
+ "OSD",
+ "SDCARD_DETECT",
"RX_BIND",
- "INVERTER", "LED_STRIP",
+ "INVERTER",
+ "LED_STRIP",
};
diff --git a/src/main/drivers/resource.h b/src/main/drivers/resource.h
index e8e0636781..e554f98459 100644
--- a/src/main/drivers/resource.h
+++ b/src/main/drivers/resource.h
@@ -1,9 +1,22 @@
+/*
+ * 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 RESOURCE_INDEX(x) (x + 1)
-#define RESOURCE_SOFT_OFFSET 10
-
typedef enum {
OWNER_FREE = 0,
OWNER_PWMINPUT,
@@ -38,6 +51,7 @@ typedef enum {
OWNER_MPU_EXTI,
OWNER_BARO_EXTI,
OWNER_USB,
+ OWNER_USB_DETECT,
OWNER_BEEPER,
OWNER_OSD,
OWNER_SDCARD_DETECT,
@@ -49,3 +63,5 @@ typedef enum {
extern const char * const ownerNames[OWNER_TOTAL_COUNT];
+#define RESOURCE_INDEX(x) (x + 1)
+#define RESOURCE_SOFT_OFFSET 10