diff --git a/src/main/drivers/barometer_bmp085.c b/src/main/drivers/barometer_bmp085.c old mode 100755 new mode 100644 index 3cf379a206..a67f34f3fe --- a/src/main/drivers/barometer_bmp085.c +++ b/src/main/drivers/barometer_bmp085.c @@ -172,8 +172,8 @@ bool bmp085Detect(const bmp085Config_t *config, baro_t *baro) // Enable and set EXTI10-15 Interrupt to the lowest priority NVIC_InitStructure.NVIC_IRQChannel = EXTI15_10_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = BARO_EXTIRQ_PRIORITY; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = BARO_EXTIRQ_SUBPRIORITY; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_BARO_EXT); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_BARO_EXT); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); } diff --git a/src/main/drivers/bus_i2c_stm32f10x.c b/src/main/drivers/bus_i2c_stm32f10x.c old mode 100755 new mode 100644 index d5cefe6312..fa0e27c439 --- a/src/main/drivers/bus_i2c_stm32f10x.c +++ b/src/main/drivers/bus_i2c_stm32f10x.c @@ -343,15 +343,15 @@ void i2cInit(I2CDevice index) // I2C ER Interrupt nvic.NVIC_IRQChannel = i2cHardwareMap[index].er_irq; - nvic.NVIC_IRQChannelPreemptionPriority = I2C_ER_IRQ_PRIORITY; - nvic.NVIC_IRQChannelSubPriority = I2C_ER_IRQ_SUBPRIORITY; + nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER); + nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_ER); nvic.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&nvic); // I2C EV Interrupt nvic.NVIC_IRQChannel = i2cHardwareMap[index].ev_irq; - nvic.NVIC_IRQChannelPreemptionPriority = I2C_EV_IRQ_PRIORITY; - nvic.NVIC_IRQChannelSubPriority = I2C_EV_IRQ_SUBPRIORITY; + nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_EV); + nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_EV); NVIC_Init(&nvic); } diff --git a/src/main/drivers/light_ws2811strip_stm32f10x.c b/src/main/drivers/light_ws2811strip_stm32f10x.c index 2f696844c9..1462114324 100644 --- a/src/main/drivers/light_ws2811strip_stm32f10x.c +++ b/src/main/drivers/light_ws2811strip_stm32f10x.c @@ -97,8 +97,8 @@ void ws2811LedStripHardwareInit(void) NVIC_InitTypeDef NVIC_InitStructure; NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel6_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = WS2811_DMA_IRQ_PRIORITY; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = WS2811_DMA_IRQ_SUBPRIORITY; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_WS2811_DMA); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_WS2811_DMA); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); diff --git a/src/main/drivers/light_ws2811strip_stm32f30x.c b/src/main/drivers/light_ws2811strip_stm32f30x.c index 895fe44e74..49e8eae128 100644 --- a/src/main/drivers/light_ws2811strip_stm32f30x.c +++ b/src/main/drivers/light_ws2811strip_stm32f30x.c @@ -102,8 +102,8 @@ void ws2811LedStripHardwareInit(void) NVIC_InitTypeDef NVIC_InitStructure; NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel3_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = WS2811_DMA_IRQ_PRIORITY; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = WS2811_DMA_IRQ_SUBPRIORITY; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_WS2811_DMA); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_WS2811_DMA); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); diff --git a/src/main/drivers/nvic.h b/src/main/drivers/nvic.h index f61d64b61b..71e4f17815 100644 --- a/src/main/drivers/nvic.h +++ b/src/main/drivers/nvic.h @@ -3,54 +3,25 @@ #define NVIC_PRIORITY_GROUPING NVIC_PriorityGroup_2 -// can't use 0 -#define MAX_IRQ_PRIORITY 0 -#define MAX_IRQ_SUBPRIORITY 1 - -#define TIMER_IRQ_PRIORITY 1 -#define TIMER_IRQ_SUBPRIORITY 1 - -#define BARO_EXTIRQ_PRIORITY 0x0f -#define BARO_EXTIRQ_SUBPRIORITY 0x0f - -#define WS2811_DMA_IRQ_PRIORITY 1 // TODO - is there some reason to use high priority? (or to use DMA IRQ at all?) -#define WS2811_DMA_IRQ_SUBPRIORITY 2 - -#define SERIALUART1_TXDMA_IRQ_PRIORITY 1 -#define SERIALUART1_TXDMA_IRQ_SUBPRIORITY 1 - -#define SERIALUART1_RXDMA_IRQ_PRIORITY 1 -#define SERIALUART1_RXDMA_IRQ_SUBPRIORITY 1 - -#define SERIALUART1_IRQ_PRIORITY 1 -#define SERIALUART1_IRQ_SUBPRIORITY 1 - -#define SERIALUART2_TXDMA_IRQ_PRIORITY 1 -#define SERIALUART2_TXDMA_IRQ_SUBPRIORITY 0 - -#define SERIALUART2_RXDMA_IRQ_PRIORITY 1 -#define SERIALUART2_RXDMA_IRQ_SUBPRIORITY 1 - -#define SERIALUART2_IRQ_PRIORITY 1 -#define SERIALUART2_IRQ_SUBPRIORITY 2 - -#define SERIALUART3_IRQ_PRIORITY 1 -#define SERIALUART3_IRQ_SUBPRIORITY 2 - -#define I2C_ER_IRQ_PRIORITY 0 -#define I2C_ER_IRQ_SUBPRIORITY 0 -#define I2C_EV_IRQ_PRIORITY 0 -#define I2C_EV_IRQ_SUBPRIORITY 0 - -#define USB_IRQ_PRIORITY 2 -#define USB_IRQ_SUBPRIORITY 0 -#define USB_WUP_IRQ_PRIORITY 1 -#define USB_WUP_IRQ_SUBPRIORITY 0 - -#define CALLBACK_IRQ_PRIORITY 0x0f -#define CALLBACK_IRQ_SUBPRIORITY 0x0f +// can't use 0 +#define NVIC_PRIO_MAX NVIC_BUILD_PRIORITY(0, 1) +#define NVIC_PRIO_TIMER NVIC_BUILD_PRIORITY(1, 1) +#define NVIC_PRIO_BARO_EXT NVIC_BUILD_PRIORITY(0x0f, 0x0f) +#define NVIC_PRIO_WS2811_DMA NVIC_BUILD_PRIORITY(1, 2) // TODO - is there some reason to use high priority? (or to use DMA IRQ at all?) +#define NVIC_PRIO_SERIALUART1_TXDMA NVIC_BUILD_PRIORITY(1, 1) +#define NVIC_PRIO_SERIALUART1_RXDMA NVIC_BUILD_PRIORITY(1, 1) +#define NVIC_PRIO_SERIALUART1 NVIC_BUILD_PRIORITY(1, 1) +#define NVIC_PRIO_SERIALUART2_TXDMA NVIC_BUILD_PRIORITY(1, 0) +#define NVIC_PRIO_SERIALUART2_RXDMA NVIC_BUILD_PRIORITY(1, 1) +#define NVIC_PRIO_SERIALUART2 NVIC_BUILD_PRIORITY(1, 2) +#define NVIC_PRIO_SERIALUART3 NVIC_BUILD_PRIORITY(1, 2) +#define NVIC_PRIO_I2C_ER NVIC_BUILD_PRIORITY(0, 0) +#define NVIC_PRIO_I2C_EV NVIC_BUILD_PRIORITY(0, 0) +#define NVIC_PRIO_USB NVIC_BUILD_PRIORITY(2, 0) +#define NVIC_PRIO_USB_WUP NVIC_BUILD_PRIORITY(1, 0) +#define NVIC_PRIO_CALLBACK NVIC_BUILD_PRIORITY(0x0f, 0x0f) // utility macros to join/split priority -#define NVIC_BUILD_PRIORITY(base,sub) ((((base)<<(4-(7-(NVIC_PRIORITY_GROUPING>>8))))|((sub)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING>>8)))))<<4) -#define NVIC_SPLIT_PRIORITY_BASE(prio) (((prio)>>(4-(7-(NVIC_PRIORITY_GROUPING>>8))))>>4) -#define NVIC_SPLIT_PRIORITY_SUB(prio) (((prio)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING>>8))))>>4) +#define NVIC_BUILD_PRIORITY(base,sub) (((((base)<<(4-(7-(NVIC_PRIORITY_GROUPING>>8))))|((sub)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING>>8)))))<<4)&0xf0) +#define NVIC_PRIORITY_BASE(prio) (((prio)>>(4-(7-(NVIC_PRIORITY_GROUPING>>8))))>>4) +#define NVIC_PRIORITY_SUB(prio) (((prio)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING>>8))))>>4) diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/serial_uart.h b/src/main/drivers/serial_uart.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/serial_uart_stm32f10x.c b/src/main/drivers/serial_uart_stm32f10x.c old mode 100755 new mode 100644 index e0e0915946..45f2da8821 --- a/src/main/drivers/serial_uart_stm32f10x.c +++ b/src/main/drivers/serial_uart_stm32f10x.c @@ -117,8 +117,8 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode) // DMA TX Interrupt NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel4_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = SERIALUART1_TXDMA_IRQ_PRIORITY; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = SERIALUART1_TXDMA_IRQ_SUBPRIORITY; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART1_TXDMA); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART1_TXDMA); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); @@ -199,8 +199,8 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode) // RX/TX Interrupt NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = SERIALUART2_IRQ_PRIORITY; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = SERIALUART2_IRQ_SUBPRIORITY; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART2); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART2); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); @@ -261,8 +261,8 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode) // RX/TX Interrupt NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = SERIALUART3_IRQ_PRIORITY; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = SERIALUART3_IRQ_SUBPRIORITY; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART3); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART3); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index 0adc724684..7870fc9838 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -108,15 +108,15 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode) // DMA TX Interrupt NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel4_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = SERIALUART1_TXDMA_IRQ_PRIORITY; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = SERIALUART1_TXDMA_IRQ_SUBPRIORITY; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART1_TXDMA); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART1_TXDMA); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); #ifndef USE_USART1_RX_DMA NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = SERIALUART1_RXDMA_IRQ_PRIORITY; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = SERIALUART1_RXDMA_IRQ_SUBPRIORITY; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART1_RXDMA); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART1_RXDMA); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); #endif @@ -179,16 +179,16 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode) #ifdef USE_USART2_TX_DMA // DMA TX Interrupt NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel7_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = SERIALUART2_TXDMA_IRQ_PRIORITY; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = SERIALUART2_TXDMA_IRQ_SUBPRIORITY; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART2_TXDMA); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART2_TXDMA); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); #endif #ifndef USE_USART2_RX_DMA NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = SERIALUART2_RXDMA_IRQ_PRIORITY; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = SERIALUART2_RXDMA_IRQ_SUBPRIORITY; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART2_RXDMA); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART2_RXDMA); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); #endif diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index 751449c22f..13f7bbf6a8 100644 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -313,8 +313,8 @@ void timerNVICConfigure(uint8_t irq) NVIC_InitTypeDef NVIC_InitStructure; NVIC_InitStructure.NVIC_IRQChannel = irq; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = TIMER_IRQ_PRIORITY; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = TIMER_IRQ_SUBPRIORITY; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); } diff --git a/src/main/vcp/hw_config.c b/src/main/vcp/hw_config.c index 80b1a8a2e6..835cb8293d 100644 --- a/src/main/vcp/hw_config.c +++ b/src/main/vcp/hw_config.c @@ -195,15 +195,15 @@ void USB_Interrupts_Config(void) /* Enable the USB interrupt */ NVIC_InitStructure.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = USB_IRQ_PRIORITY; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = USB_IRQ_SUBPRIORITY; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_USB); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_USB); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); /* Enable the USB Wake-up interrupt */ NVIC_InitStructure.NVIC_IRQChannel = USBWakeUp_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = USB_WUP_IRQ_PRIORITY; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = USB_WUP_IRQ_SUBPRIORITY; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_USB_WUP); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_USB_WUP); NVIC_Init(&NVIC_InitStructure); }