Centralized NVIC priorities

- NVIC priorities are moved to separate file, all values are replaced wit symbolic names. Priorities should be the same.
- tiny change in DMA initialization
This commit is contained in:
Petr Ledvina 2014-10-23 16:45:14 +02:00
parent 1604f856b8
commit e686b4504e
13 changed files with 120 additions and 49 deletions

View File

@ -27,6 +27,7 @@
#include "gpio.h"
#include "system.h"
#include "bus_i2c.h"
#include "nvic.h"
#include "barometer_bmp085.h"
@ -171,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 = 0x0F;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0x0F;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = BARO_EXTIRQ_PRIORITY;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = BARO_EXTIRQ_SUBPRIORITY;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}

View File

@ -27,6 +27,7 @@
#include "system.h"
#include "bus_i2c.h"
#include "nvic.h"
#ifndef SOFT_I2C
@ -342,14 +343,15 @@ void i2cInit(I2CDevice index)
// I2C ER Interrupt
nvic.NVIC_IRQChannel = i2cHardwareMap[index].er_irq;
nvic.NVIC_IRQChannelPreemptionPriority = 0;
nvic.NVIC_IRQChannelSubPriority = 0;
nvic.NVIC_IRQChannelPreemptionPriority = I2C_ER_IRQ_PRIORITY;
nvic.NVIC_IRQChannelSubPriority = I2C_ER_IRQ_SUBPRIORITY;
nvic.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&nvic);
// I2C EV Interrupt
nvic.NVIC_IRQChannel = i2cHardwareMap[index].ev_irq;
nvic.NVIC_IRQChannelPreemptionPriority = 0;
nvic.NVIC_IRQChannelPreemptionPriority = I2C_EV_IRQ_PRIORITY;
nvic.NVIC_IRQChannelSubPriority = I2C_EV_IRQ_SUBPRIORITY;
NVIC_Init(&nvic);
}

View File

@ -22,6 +22,7 @@
#include "common/color.h"
#include "drivers/light_ws2811strip.h"
#include "nvic.h"
void ws2811LedStripHardwareInit(void)
{
@ -96,8 +97,8 @@ void ws2811LedStripHardwareInit(void)
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel6_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = WS2811_DMA_IRQ_PRIORITY;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = WS2811_DMA_IRQ_SUBPRIORITY;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);

View File

@ -21,6 +21,7 @@
#include "platform.h"
#include "gpio.h"
#include "nvic.h"
#include "common/color.h"
#include "drivers/light_ws2811strip.h"
@ -101,8 +102,8 @@ void ws2811LedStripHardwareInit(void)
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel3_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = WS2811_DMA_IRQ_PRIORITY;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = WS2811_DMA_IRQ_SUBPRIORITY;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);

56
src/main/drivers/nvic.h Normal file
View File

@ -0,0 +1,56 @@
#pragma once
#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
// 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)

View File

@ -23,6 +23,7 @@
#include "platform.h"
#include "build_config.h"
#include "nvic.h"
#include "gpio.h"
#include "timer.h"
@ -39,6 +40,7 @@
#define PWM_PORTS_OR_PPM_CAPTURE_COUNT PWM_INPUT_PORT_COUNT
#endif
// TODO - change to timer cloks ticks
#define INPUT_FILTER_TO_HELP_WITH_NOISE_FROM_OPENLRS_TELEMETRY_RX 0x03
static inputFilteringMode_e inputFilteringMode;

View File

@ -25,6 +25,7 @@
#include "build_config.h"
#include "nvic.h"
#include "system.h"
#include "gpio.h"
#include "timer.h"

View File

@ -64,7 +64,6 @@ static void uartReconfigure(uartPort_t *uartPort)
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion)
{
UNUSED(inversion);
DMA_InitTypeDef DMA_InitStructure;
uartPort_t *s = NULL;
@ -106,18 +105,20 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
uartReconfigure(s);
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = s->rxDMAPeripheralBaseAddr;
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
// Receive DMA or IRQ
DMA_InitTypeDef DMA_InitStructure;
if (mode & MODE_RX) {
if (s->rxDMAChannel) {
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = s->rxDMAPeripheralBaseAddr;
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
DMA_InitStructure.DMA_BufferSize = s->port.rxBufferSize;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
@ -133,18 +134,18 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
}
}
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = s->txDMAPeripheralBaseAddr;
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
// Transmit DMA or IRQ
if (mode & MODE_TX) {
if (s->txDMAChannel) {
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = s->txDMAPeripheralBaseAddr;
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
DMA_InitStructure.DMA_BufferSize = s->port.txBufferSize;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;

View File

@ -30,6 +30,7 @@
#include "system.h"
#include "gpio.h"
#include "nvic.h"
#include "serial.h"
#include "serial_uart.h"
@ -116,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 = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = SERIALUART1_TXDMA_IRQ_PRIORITY;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = SERIALUART1_TXDMA_IRQ_SUBPRIORITY;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
@ -198,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 = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = SERIALUART2_IRQ_PRIORITY;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = SERIALUART2_IRQ_SUBPRIORITY;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
@ -260,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 = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = SERIALUART3_IRQ_PRIORITY;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = SERIALUART3_IRQ_SUBPRIORITY;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);

View File

@ -31,6 +31,7 @@
#include "system.h"
#include "gpio.h"
#include "nvic.h"
#include "serial.h"
#include "serial_uart.h"
@ -107,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 = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = SERIALUART1_TXDMA_IRQ_PRIORITY;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = SERIALUART1_TXDMA_IRQ_SUBPRIORITY;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
#ifndef USE_USART1_RX_DMA
NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = SERIALUART1_RXDMA_IRQ_PRIORITY;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = SERIALUART1_RXDMA_IRQ_SUBPRIORITY;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
#endif
@ -178,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 = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = SERIALUART2_TXDMA_IRQ_PRIORITY;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = SERIALUART2_TXDMA_IRQ_SUBPRIORITY;
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 = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = SERIALUART2_RXDMA_IRQ_PRIORITY;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = SERIALUART2_RXDMA_IRQ_SUBPRIORITY;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
#endif

View File

@ -26,6 +26,7 @@
#include "gpio.h"
#include "light_led.h"
#include "sound_beeper.h"
#include "nvic.h"
#include "system.h"
@ -73,7 +74,7 @@ void systemInit(void)
NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0);
#endif
// Configure NVIC preempt/priority groups
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
#ifdef STM32F10X
// Turn on clocks for stuff we use

View File

@ -21,6 +21,7 @@
#include <string.h>
#include "platform.h"
#include "nvic.h"
#include "gpio.h"
#include "system.h"
@ -312,8 +313,8 @@ void timerNVICConfigure(uint8_t irq)
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = irq;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = TIMER_IRQ_PRIORITY;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = TIMER_IRQ_SUBPRIORITY;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}

View File

@ -37,6 +37,7 @@
#include <stdbool.h>
#include "drivers/system.h"
#include "drivers/nvic.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
@ -190,18 +191,19 @@ void USB_Interrupts_Config(void)
NVIC_InitTypeDef NVIC_InitStructure;
/* 2 bit for pre-emption priority, 2 bits for subpriority */
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING); // is this really neccesary?
/* Enable the USB interrupt */
NVIC_InitStructure.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = USB_IRQ_PRIORITY;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = USB_IRQ_SUBPRIORITY;
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 = 1;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = USB_WUP_IRQ_PRIORITY;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = USB_WUP_IRQ_SUBPRIORITY;
NVIC_Init(&NVIC_InitStructure);
}