1
0
mirror of https://github.com/trezor/trezor-firmware.git synced 2025-01-03 12:00:59 +00:00

refactor(core/embed): simplify irq priorities

[no changelog]
This commit is contained in:
cepetr 2024-06-20 12:43:35 +02:00 committed by cepetr
parent 3fb55a373d
commit d558950950
22 changed files with 124 additions and 210 deletions

View File

@ -62,6 +62,9 @@
#ifdef USE_HASH_PROCESSOR #ifdef USE_HASH_PROCESSOR
#include "hash_processor.h" #include "hash_processor.h"
#endif #endif
#ifdef STM32U5
#include "irq.h"
#endif
#include "model.h" #include "model.h"
#include "usb.h" #include "usb.h"
@ -339,7 +342,7 @@ __attribute__((noreturn)) void jump_to_fw_through_reset(void) {
display_finish_actions(); display_finish_actions();
display_fade(display_backlight(-1), 0, 200); display_fade(display_backlight(-1), 0, 200);
__disable_irq(); disable_irq();
delete_secrets(); delete_secrets();
NVIC_SystemReset(); NVIC_SystemReset();
for (;;) for (;;)

View File

@ -55,7 +55,7 @@ extern __IO uint32_t uwTick;
// and works when interrupts are disabled. This function is intended to be // and works when interrupts are disabled. This function is intended to be
// used only by the ST HAL functions. // used only by the ST HAL functions.
void HAL_Delay(uint32_t Delay) { void HAL_Delay(uint32_t Delay) {
if (query_irq() == IRQ_STATE_ENABLED) { if (IS_IRQ_ENABLED(query_irq())) {
// IRQs enabled, so can use systick counter to do the delay // IRQs enabled, so can use systick counter to do the delay
uint32_t start = uwTick; uint32_t start = uwTick;
// Wraparound of tick is taken care of by 2's complement arithmetic. // Wraparound of tick is taken care of by 2's complement arithmetic.
@ -72,7 +72,7 @@ void HAL_Delay(uint32_t Delay) {
// Core delay function that does an efficient sleep and may switch thread context. // Core delay function that does an efficient sleep and may switch thread context.
// If IRQs are enabled then we must have the GIL. // If IRQs are enabled then we must have the GIL.
void mp_hal_delay_ms(mp_uint_t Delay) { void mp_hal_delay_ms(mp_uint_t Delay) {
if (query_irq() == IRQ_STATE_ENABLED) { if (IS_IRQ_ENABLED(query_irq())) {
// IRQs enabled, so can use systick counter to do the delay // IRQs enabled, so can use systick counter to do the delay
uint32_t start = uwTick; uint32_t start = uwTick;
// Wraparound of tick is taken care of by 2's complement arithmetic. // Wraparound of tick is taken care of by 2's complement arithmetic.
@ -95,7 +95,7 @@ void mp_hal_delay_ms(mp_uint_t Delay) {
// delay for given number of microseconds // delay for given number of microseconds
void mp_hal_delay_us(mp_uint_t usec) { void mp_hal_delay_us(mp_uint_t usec) {
if (query_irq() == IRQ_STATE_ENABLED) { if (IS_IRQ_ENABLED(query_irq())) {
// IRQs enabled, so can use systick counter to do the delay // IRQs enabled, so can use systick counter to do the delay
uint32_t start = mp_hal_ticks_us(); uint32_t start = mp_hal_ticks_us();
while (mp_hal_ticks_us() - start < usec) { while (mp_hal_ticks_us() - start < usec) {

View File

@ -130,6 +130,8 @@ static void optiga_log_hex(const char *prefix, const uint8_t *data,
#endif #endif
int main(void) { int main(void) {
svc_init();
random_delays_init(); random_delays_init();
#ifdef RDI #ifdef RDI

View File

@ -776,6 +776,7 @@ void cpuid_read(void) {
#define BACKLIGHT_NORMAL 150 #define BACKLIGHT_NORMAL 150
int main(void) { int main(void) {
svc_init();
display_reinit(); display_reinit();
display_orientation(0); display_orientation(0);
random_delays_init(); random_delays_init();

View File

@ -384,7 +384,7 @@ void display_setup_te_interrupt(void) {
HAL_EXTI_SetConfigLine(&EXTI_Handle, &EXTI_Config); HAL_EXTI_SetConfigLine(&EXTI_Handle, &EXTI_Config);
// setup interrupt for tearing effect pin // setup interrupt for tearing effect pin
HAL_NVIC_SetPriority(DISPLAY_TE_INTERRUPT_NUM, IRQ_PRI_DMA, 0); NVIC_SetPriority(DISPLAY_TE_INTERRUPT_NUM, IRQ_PRI_NORMAL);
#endif #endif
} }
#endif #endif
@ -564,7 +564,7 @@ void display_sync(void) {}
#ifndef BOARDLOADER #ifndef BOARDLOADER
void DISPLAY_TE_INTERRUPT_HANDLER(void) { void DISPLAY_TE_INTERRUPT_HANDLER(void) {
HAL_NVIC_DisableIRQ(DISPLAY_TE_INTERRUPT_NUM); NVIC_DisableIRQ(DISPLAY_TE_INTERRUPT_NUM);
if (act_frame_buffer == 1) { if (act_frame_buffer == 1) {
bg_copy_start_const_out_8((uint8_t *)PhysFrameBuffer1, bg_copy_start_const_out_8((uint8_t *)PhysFrameBuffer1,

View File

@ -1,50 +1,33 @@
// clang-format off
/* /*
* This file is part of the MicroPython project, http://micropython.org/ * This file is part of the Trezor project, https://trezor.io/
* *
* The MIT License (MIT) * Copyright (c) SatoshiLabs
* *
* Copyright (c) 2013, 2014 Damien P. George * This program 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.
* *
* Permission is hereby granted, free of charge, to any person obtaining a copy * This program is distributed in the hope that it will be useful,
* of this software and associated documentation files (the "Software"), to deal * but WITHOUT ANY WARRANTY; without even the implied warranty of
* in the Software without restriction, including without limitation the rights * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell * GNU General Public License for more details.
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
* *
* The above copyright notice and this permission notice shall be included in * You should have received a copy of the GNU General Public License
* all copies or substantial portions of the Software. * along with this program. If not, see <http://www.gnu.org/licenses/>.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/ */
#ifndef MICROPY_INCLUDED_STM32_IRQ_H
#define MICROPY_INCLUDED_STM32_IRQ_H #ifndef TREZORHAL_IRQ_H
#define TREZORHAL_IRQ_H
#include STM32_HAL_H #include STM32_HAL_H
#include <stdint.h> #include <stdint.h>
// Use this macro together with NVIC_SetPriority to indicate that an IRQn is non-negative, // Enables simple IRQ statistics for debugging
// which helps the compiler optimise the resulting inline function.
#define IRQn_NONNEG(pri) ((pri) & 0x7f)
// these states correspond to values from query_irq, enable_irq and disable_irq
#define IRQ_STATE_DISABLED (0x00000001)
#define IRQ_STATE_ENABLED (0x00000000)
// Enable this to get a count for the number of times each irq handler is called,
// accessible via pyb.irq_stats().
#define IRQ_ENABLE_STATS (0) #define IRQ_ENABLE_STATS (0)
#if IRQ_ENABLE_STATS #if IRQ_ENABLE_STATS
#define IRQ_STATS_MAX (128) #define IRQ_STATS_MAX (128)
extern uint32_t irq_stats[IRQ_STATS_MAX]; extern uint32_t irq_stats[IRQ_STATS_MAX];
#define IRQ_ENTER(irq) ++irq_stats[irq] #define IRQ_ENTER(irq) ++irq_stats[irq]
#define IRQ_EXIT(irq) #define IRQ_EXIT(irq)
@ -53,111 +36,34 @@ extern uint32_t irq_stats[IRQ_STATS_MAX];
#define IRQ_EXIT(irq) #define IRQ_EXIT(irq)
#endif #endif
static inline uint32_t query_irq(void) { // Checks if interrupts are enabled
return __get_PRIMASK(); #define IS_IRQ_ENABLED(state) (((state) & 1) == 0)
}
static inline void enable_irq(uint32_t state) { // Get the current value of the CPU's exception mask register.
__set_PRIMASK(state); // The least significant bit indicates if interrupts are enabled or disabled.
} static inline uint32_t query_irq(void) { return __get_PRIMASK(); }
// Restore the CPU's exception mask register to a previous state
static inline void enable_irq(uint32_t state) { __set_PRIMASK(state); }
// Disable all interrupts and return the current state of the
// CPU's exception mask register
static inline uint32_t disable_irq(void) { static inline uint32_t disable_irq(void) {
uint32_t state = __get_PRIMASK(); uint32_t state = __get_PRIMASK();
__disable_irq(); __disable_irq();
return state; return state;
} }
// enable_irq and disable_irq are defined inline in mpconfigport.h // IRQ priority levels used throughout the system
#if __CORTEX_M >= 0x03 // Highest priority in the system (only RESET, NMI, and
// HardFault can preempt exceptions at this priority level)
#define IRQ_PRI_HIGHEST NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 0, 0)
// irqs with a priority value greater or equal to "pri" will be disabled // Standard priority for common interrupt handlers
// "pri" should be between 1 and 15 inclusive #define IRQ_PRI_NORMAL NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 8, 0)
static inline uint32_t raise_irq_pri(uint32_t pri) {
uint32_t basepri = __get_BASEPRI();
// If non-zero, the processor does not process any exception with a
// priority value greater than or equal to BASEPRI.
// When writing to BASEPRI_MAX the write goes to BASEPRI only if either:
// - Rn is non-zero and the current BASEPRI value is 0
// - Rn is non-zero and less than the current BASEPRI value
pri <<= (8 - __NVIC_PRIO_BITS);
__ASM volatile ("msr basepri_max, %0" : : "r" (pri) : "memory");
return basepri;
}
// "basepri" should be the value returned from raise_irq_pri // Lowest priority in the system used by SVC and PENDSV exception handlers
static inline void restore_irq_pri(uint32_t basepri) { #define IRQ_PRI_LOWEST NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 15, 0)
__set_BASEPRI(basepri);
}
#else #endif // TREZORHAL_IRQ_H
static inline uint32_t raise_irq_pri(uint32_t pri) {
return disable_irq();
}
// "state" should be the value returned from raise_irq_pri
static inline void restore_irq_pri(uint32_t state) {
enable_irq(state);
}
#endif
// IRQ priority definitions.
//
// Lower number implies higher interrupt priority.
//
// The default priority grouping is set to NVIC_PRIORITYGROUP_4 in the
// HAL_Init function. This corresponds to 4 bits for the priority field
// and 0 bits for the sub-priority field (which means that for all intensive
// purposes that the sub-priorities below are ignored).
//
// While a given interrupt is being processed, only higher priority (lower number)
// interrupts will preempt a given interrupt. If sub-priorities are active
// then the sub-priority determines the order that pending interrupts of
// a given priority are executed. This is only meaningful if 2 or more
// interrupts of the same priority are pending at the same time.
//
// The priority of the SysTick timer is determined from the TICK_INT_PRIORITY
// value which is normally set to 0 in the stm32f4xx_hal_conf.h file.
//
// The following interrupts are arranged from highest priority to lowest
// priority to make it a bit easier to figure out.
//#def IRQ_PRI_SYSTICK NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 0, 0)
// The UARTs have no FIFOs, so if they don't get serviced quickly then characters
// get dropped. The handling for each character only consumes about 0.5 usec
#define IRQ_PRI_UART NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 1, 0)
// SDIO must be higher priority than DMA for SDIO DMA transfers to work.
#define IRQ_PRI_SDIO NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 4, 0)
// DMA should be higher priority than USB, since USB Mass Storage calls
// into the sdcard driver which waits for the DMA to complete.
#define IRQ_PRI_DMA NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 5, 0)
// Flash IRQ (used for flushing storage cache) must be at the same priority as
// the USB IRQs, so that the IRQ priority can be raised to this level to disable
// both the USB and cache flushing, when storage transfers are in progress.
#define IRQ_PRI_FLASH NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 6, 0)
#define IRQ_PRI_OTG_FS NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 6, 0)
#define IRQ_PRI_OTG_HS NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 6, 0)
#define IRQ_PRI_TIM5 NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 6, 0)
#define IRQ_PRI_CAN NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 7, 0)
#define IRQ_PRI_SPI NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 8, 0)
// Interrupt priority for non-special timers.
#define IRQ_PRI_TIMX NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 13, 0)
#define IRQ_PRI_EXTINT NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 14, 0)
//?#define IRQ_PRI_RTC_WKUP NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 15, 0)
// !@# TAMPER interrupt priority should be probably much higher
#define IRQ_PRI_TAMP NVIC_EncodePriority(NVIC_PRIORITYGROUP_4, 15, 0)
#endif // MICROPY_INCLUDED_STM32_IRQ_H

View File

@ -134,7 +134,7 @@ void HAL_SD_MspInit(SD_HandleTypeDef *hsd) {
SDMMC_CLK_ENABLE(); SDMMC_CLK_ENABLE();
// NVIC configuration for SDIO interrupts // NVIC configuration for SDIO interrupts
svc_setpriority(SDMMC_IRQn, IRQ_PRI_SDIO); svc_setpriority(SDMMC_IRQn, IRQ_PRI_NORMAL);
svc_enableIRQ(SDMMC_IRQn); svc_enableIRQ(SDMMC_IRQn);
} }

View File

@ -19,6 +19,7 @@
/* Includes ------------------------------------------------------------------*/ /* Includes ------------------------------------------------------------------*/
#include "sdram.h" #include "sdram.h"
#include "irq.h"
/** @addtogroup BSP /** @addtogroup BSP
* @{ * @{
@ -397,8 +398,8 @@ void BSP_SDRAM_MspInit(SDRAM_HandleTypeDef *hsdram, void *Params) {
HAL_DMA_Init(&dmaHandle); HAL_DMA_Init(&dmaHandle);
/* NVIC configuration for DMA transfer complete interrupt */ /* NVIC configuration for DMA transfer complete interrupt */
HAL_NVIC_SetPriority(SDRAM_DMAx_IRQn, 0x0F, 0); NVIC_SetPriority(SDRAM_DMAx_IRQn, IRQ_PRI_NORMAL);
HAL_NVIC_EnableIRQ(SDRAM_DMAx_IRQn); NVIC_EnableIRQ(SDRAM_DMAx_IRQn);
} /* of if(hsdram != (SDRAM_HandleTypeDef *)NULL) */ } /* of if(hsdram != (SDRAM_HandleTypeDef *)NULL) */
} }
@ -413,7 +414,7 @@ void BSP_SDRAM_MspDeInit(SDRAM_HandleTypeDef *hsdram, void *Params) {
if (hsdram != (SDRAM_HandleTypeDef *)NULL) { if (hsdram != (SDRAM_HandleTypeDef *)NULL) {
/* Disable NVIC configuration for DMA interrupt */ /* Disable NVIC configuration for DMA interrupt */
HAL_NVIC_DisableIRQ(SDRAM_DMAx_IRQn); NVIC_DisableIRQ(SDRAM_DMAx_IRQn);
/* Deinitialize the stream for new transfer */ /* Deinitialize the stream for new transfer */
dma_handle.Instance = SDRAM_DMAx_STREAM; dma_handle.Instance = SDRAM_DMAx_STREAM;

View File

@ -5,16 +5,26 @@
#include "../mpu.h" #include "../mpu.h"
#include "common.h" #include "common.h"
#include "display.h" #include "display.h"
#include "irq.h"
#include "supervise.h" #include "supervise.h"
#ifdef ARM_USER_MODE #ifdef ARM_USER_MODE
void svc_init(void) {
NVIC_SetPriority(SVCall_IRQn, IRQ_PRI_HIGHEST);
// We need to ensure that SysTick has the expected priority.
// The SysTick priority is configured in the boardloader,
// and some early versions didn't set this properly.
NVIC_SetPriority(SysTick_IRQn, IRQ_PRI_HIGHEST);
}
#ifdef STM32U5 #ifdef STM32U5
extern uint32_t g_boot_command; extern uint32_t g_boot_command;
__attribute__((noreturn)) static void _reboot_to_bootloader( __attribute__((noreturn)) static void _reboot_to_bootloader(
boot_command_t boot_command) { boot_command_t boot_command) {
g_boot_command = boot_command; g_boot_command = boot_command;
__disable_irq(); disable_irq();
delete_secrets(); delete_secrets();
NVIC_SystemReset(); NVIC_SystemReset();
} }
@ -54,10 +64,10 @@ void SVC_C_Handler(uint32_t *stack) {
uint8_t svc_number = ((uint8_t *)stack[6])[-2]; uint8_t svc_number = ((uint8_t *)stack[6])[-2];
switch (svc_number) { switch (svc_number) {
case SVC_ENABLE_IRQ: case SVC_ENABLE_IRQ:
HAL_NVIC_EnableIRQ(stack[0]); NVIC_EnableIRQ(stack[0]);
break; break;
case SVC_DISABLE_IRQ: case SVC_DISABLE_IRQ:
HAL_NVIC_DisableIRQ(stack[0]); NVIC_DisableIRQ(stack[0]);
break; break;
case SVC_SET_PRIORITY: case SVC_SET_PRIORITY:
NVIC_SetPriority(stack[0], stack[1]); NVIC_SetPriority(stack[0], stack[1]);
@ -106,7 +116,7 @@ void SVC_C_Handler(uint32_t *stack) {
__attribute__((naked)) void SVC_Handler(void) { __attribute__((naked)) void SVC_Handler(void) {
__asm volatile( __asm volatile(
" tst lr, #4 \n" // Test Bit 3 to see which stack pointer we should " tst lr, #4 \n" // Test Bit 3 to see which stack pointer we should
// use. // use
" ite eq \n" // Tell the assembler that the nest 2 instructions " ite eq \n" // Tell the assembler that the nest 2 instructions
// are if-then-else // are if-then-else
" mrseq r0, msp \n" // Make R0 point to main stack pointer " mrseq r0, msp \n" // Make R0 point to main stack pointer

View File

@ -20,6 +20,11 @@ extern uint32_t systick_val_copy;
extern void shutdown_privileged(void); extern void shutdown_privileged(void);
extern void ensure_compatible_settings(void); extern void ensure_compatible_settings(void);
// Initializes the supervise module
//
// Must be called before invoking the first `svc_xxx` call
void svc_init(void);
static inline uint32_t is_mode_unprivileged(void) { static inline uint32_t is_mode_unprivileged(void) {
uint32_t r0; uint32_t r0;
__asm__ volatile("mrs %0, control" : "=r"(r0)); __asm__ volatile("mrs %0, control" : "=r"(r0));
@ -37,7 +42,7 @@ static inline void svc_enableIRQ(uint32_t IRQn) {
register uint32_t r0 __asm__("r0") = IRQn; register uint32_t r0 __asm__("r0") = IRQn;
__asm__ __volatile__("svc %0" ::"i"(SVC_ENABLE_IRQ), "r"(r0) : "memory"); __asm__ __volatile__("svc %0" ::"i"(SVC_ENABLE_IRQ), "r"(r0) : "memory");
} else { } else {
HAL_NVIC_EnableIRQ(IRQn); NVIC_EnableIRQ(IRQn);
} }
} }
@ -46,7 +51,7 @@ static inline void svc_disableIRQ(uint32_t IRQn) {
register uint32_t r0 __asm__("r0") = IRQn; register uint32_t r0 __asm__("r0") = IRQn;
__asm__ __volatile__("svc %0" ::"i"(SVC_DISABLE_IRQ), "r"(r0) : "memory"); __asm__ __volatile__("svc %0" ::"i"(SVC_DISABLE_IRQ), "r"(r0) : "memory");
} else { } else {
HAL_NVIC_DisableIRQ(IRQn); NVIC_DisableIRQ(IRQn);
} }
} }

View File

@ -147,7 +147,7 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
#endif #endif
/* Set USBFS Interrupt priority */ /* Set USBFS Interrupt priority */
svc_setpriority(OTG_FS_IRQn, IRQ_PRI_OTG_FS); svc_setpriority(OTG_FS_IRQn, IRQ_PRI_NORMAL);
/* Enable USBFS Interrupt */ /* Enable USBFS Interrupt */
svc_enableIRQ(OTG_FS_IRQn); svc_enableIRQ(OTG_FS_IRQn);
@ -302,7 +302,7 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
#endif // !USE_USB_HS_IN_FS #endif // !USE_USB_HS_IN_FS
/* Set USBHS Interrupt to the lowest priority */ /* Set USBHS Interrupt to the lowest priority */
svc_setpriority(OTG_HS_IRQn, IRQ_PRI_OTG_HS); svc_setpriority(OTG_HS_IRQn, IRQ_PRI_NORMAL);
/* Enable USBHS Interrupt */ /* Enable USBHS Interrupt */
svc_enableIRQ(OTG_HS_IRQn); svc_enableIRQ(OTG_HS_IRQn);

View File

@ -200,7 +200,7 @@ void display_refresh(void) {
#ifndef BOARDLOADER #ifndef BOARDLOADER
if (is_mode_handler()) { if (is_mode_handler()) {
// Disable scheduling of any new background copying // Disable scheduling of any new background copying
HAL_NVIC_DisableIRQ(DISPLAY_TE_INTERRUPT_NUM); NVIC_DisableIRQ(DISPLAY_TE_INTERRUPT_NUM);
// Wait for next TE signal. During this time the // Wait for next TE signal. During this time the
// display might be updated in the background // display might be updated in the background
wait_for_te_signal(); wait_for_te_signal();
@ -216,7 +216,7 @@ void display_refresh(void) {
drv->queue.entry[i] = FB_STATE_EMPTY; drv->queue.entry[i] = FB_STATE_EMPTY;
} }
// Enable normal processing again // Enable normal processing again
HAL_NVIC_EnableIRQ(DISPLAY_TE_INTERRUPT_NUM); NVIC_EnableIRQ(DISPLAY_TE_INTERRUPT_NUM);
} else { } else {
// Mark the buffer ready to switch to // Mark the buffer ready to switch to
drv->queue.entry[drv->queue.wix] = FB_STATE_READY; drv->queue.entry[drv->queue.wix] = FB_STATE_READY;

View File

@ -142,7 +142,7 @@ void display_io_init_te_interrupt(void) {
HAL_EXTI_SetConfigLine(&EXTI_Handle, &EXTI_Config); HAL_EXTI_SetConfigLine(&EXTI_Handle, &EXTI_Config);
// setup interrupt for tearing effect pin // setup interrupt for tearing effect pin
HAL_NVIC_SetPriority(DISPLAY_TE_INTERRUPT_NUM, IRQ_PRI_DMA, 0); NVIC_SetPriority(DISPLAY_TE_INTERRUPT_NUM, IRQ_PRI_NORMAL);
svc_enableIRQ(DISPLAY_TE_INTERRUPT_NUM); NVIC_EnableIRQ(DISPLAY_TE_INTERRUPT_NUM);
} }
#endif #endif

View File

@ -44,7 +44,7 @@ void GPDMA1_Channel0_IRQHandler(void) {
if (dma_transfer_remaining == 0) { if (dma_transfer_remaining == 0) {
// transfer finished, disable the channel // transfer finished, disable the channel
HAL_DMA_DeInit(&DMA_Handle); HAL_DMA_DeInit(&DMA_Handle);
HAL_NVIC_DisableIRQ(GPDMA1_Channel0_IRQn); NVIC_DisableIRQ(GPDMA1_Channel0_IRQn);
data_src = NULL; data_src = NULL;
data_dst = NULL; data_dst = NULL;
@ -97,8 +97,8 @@ void bg_copy_start_const_out_8(const uint8_t *src, uint8_t *dst, size_t size,
DMA_CHANNEL_SRC_SEC | DMA_CHANNEL_SRC_SEC |
DMA_CHANNEL_DEST_SEC); DMA_CHANNEL_DEST_SEC);
HAL_NVIC_SetPriority(GPDMA1_Channel0_IRQn, IRQ_PRI_DMA, 0); NVIC_SetPriority(GPDMA1_Channel0_IRQn, IRQ_PRI_NORMAL);
HAL_NVIC_EnableIRQ(GPDMA1_Channel0_IRQn); NVIC_EnableIRQ(GPDMA1_Channel0_IRQn);
HAL_DMA_Start_IT(&DMA_Handle, (uint32_t)src, (uint32_t)dst, data_to_send); HAL_DMA_Start_IT(&DMA_Handle, (uint32_t)src, (uint32_t)dst, data_to_send);
} }
@ -108,7 +108,7 @@ void bg_copy_abort(void) {
dma_data_transferred = 0; dma_data_transferred = 0;
HAL_DMA_Abort(&DMA_Handle); HAL_DMA_Abort(&DMA_Handle);
HAL_DMA_DeInit(&DMA_Handle); HAL_DMA_DeInit(&DMA_Handle);
HAL_NVIC_DisableIRQ(GPDMA1_Channel0_IRQn); NVIC_DisableIRQ(GPDMA1_Channel0_IRQn);
data_src = NULL; data_src = NULL;
data_dst = NULL; data_dst = NULL;
} }

View File

@ -59,6 +59,7 @@
/* Includes ------------------------------------------------------------------*/ /* Includes ------------------------------------------------------------------*/
#include "colors.h" #include "colors.h"
#include "irq.h"
#include "stdint.h" #include "stdint.h"
#include "string.h" #include "string.h"
#include STM32_HAL_H #include STM32_HAL_H
@ -82,15 +83,6 @@
#define BSP_BUTTON_USER_IT_PRIORITY \ #define BSP_BUTTON_USER_IT_PRIORITY \
0x0FUL /* Default is lowest priority level */ 0x0FUL /* Default is lowest priority level */
/* LCD interrupt priorities */
#define BSP_LCD_GFXMMU_IT_PRIORITY \
0x0FUL /* Default is lowest priority level \
*/
#define BSP_LCD_LTDC_IT_PRIORITY 0x0FUL /* Default is lowest priority level */
#define BSP_LCD_DSI_IT_PRIORITY 0x0FUL /* Default is lowest priority level */
/* HSPI RAM interrupt priority */
#define BSP_HSPI_RAM_IT_PRIORITY 0x0FUL /* Default is lowest priority level */
#define LCD_PIXEL_FORMAT_ARGB8888 \ #define LCD_PIXEL_FORMAT_ARGB8888 \
0x00000000U /*!< ARGB8888 LTDC pixel format \ 0x00000000U /*!< ARGB8888 LTDC pixel format \
*/ */
@ -1356,8 +1348,8 @@ static void GFXMMU_MspInit(GFXMMU_HandleTypeDef *hgfxmmu) {
__HAL_RCC_GFXMMU_CLK_ENABLE(); __HAL_RCC_GFXMMU_CLK_ENABLE();
/* Enable GFXMMU interrupt */ /* Enable GFXMMU interrupt */
HAL_NVIC_SetPriority(GFXMMU_IRQn, BSP_LCD_GFXMMU_IT_PRIORITY, 0); NVIC_SetPriority(GFXMMU_IRQn, IRQ_PRI_NORMAL);
HAL_NVIC_EnableIRQ(GFXMMU_IRQn); NVIC_EnableIRQ(GFXMMU_IRQn);
} }
/** /**
@ -1370,7 +1362,7 @@ static void GFXMMU_MspDeInit(GFXMMU_HandleTypeDef *hgfxmmu) {
UNUSED(hgfxmmu); UNUSED(hgfxmmu);
/* Disable GFXMMU interrupt */ /* Disable GFXMMU interrupt */
HAL_NVIC_DisableIRQ(GFXMMU_IRQn); NVIC_DisableIRQ(GFXMMU_IRQn);
/* GFXMMU clock disable */ /* GFXMMU clock disable */
__HAL_RCC_GFXMMU_CLK_DISABLE(); __HAL_RCC_GFXMMU_CLK_DISABLE();
@ -1389,11 +1381,11 @@ static void LTDC_MspInit(LTDC_HandleTypeDef *hltdc) {
__HAL_RCC_LTDC_CLK_ENABLE(); __HAL_RCC_LTDC_CLK_ENABLE();
/* Enable LTDC interrupt */ /* Enable LTDC interrupt */
HAL_NVIC_SetPriority(LTDC_IRQn, BSP_LCD_LTDC_IT_PRIORITY, 0); NVIC_SetPriority(LTDC_IRQn, IRQ_PRI_NORMAL);
HAL_NVIC_EnableIRQ(LTDC_IRQn); NVIC_EnableIRQ(LTDC_IRQn);
HAL_NVIC_SetPriority(LTDC_ER_IRQn, BSP_LCD_LTDC_IT_PRIORITY, 0); NVIC_SetPriority(LTDC_ER_IRQn, IRQ_PRI_NORMAL);
HAL_NVIC_EnableIRQ(LTDC_ER_IRQn); NVIC_EnableIRQ(LTDC_ER_IRQn);
} }
/** /**
@ -1406,8 +1398,8 @@ static void LTDC_MspDeInit(LTDC_HandleTypeDef *hltdc) {
UNUSED(hltdc); UNUSED(hltdc);
/* Disable LTDC interrupts */ /* Disable LTDC interrupts */
HAL_NVIC_DisableIRQ(LTDC_ER_IRQn); NVIC_DisableIRQ(LTDC_ER_IRQn);
HAL_NVIC_DisableIRQ(LTDC_IRQn); NVIC_DisableIRQ(LTDC_IRQn);
/* LTDC clock disable */ /* LTDC clock disable */
__HAL_RCC_LTDC_CLK_DISABLE(); __HAL_RCC_LTDC_CLK_DISABLE();
@ -1514,8 +1506,8 @@ static void DSI_MspInit(DSI_HandleTypeDef *hdsi) {
/* Enable DSI NVIC interrupt */ /* Enable DSI NVIC interrupt */
/* Default is lowest priority level */ /* Default is lowest priority level */
HAL_NVIC_SetPriority(DSI_IRQn, 0x0FUL, 0); NVIC_SetPriority(DSI_IRQn, IRQ_PRI_NORMAL);
HAL_NVIC_EnableIRQ(DSI_IRQn); NVIC_EnableIRQ(DSI_IRQn);
} }
/** /**
@ -1550,7 +1542,7 @@ static void DSI_MspDeInit(DSI_HandleTypeDef *hdsi) {
__HAL_RCC_DSI_RELEASE_RESET(); __HAL_RCC_DSI_RELEASE_RESET();
/* Disable DSI interrupts */ /* Disable DSI interrupts */
HAL_NVIC_DisableIRQ(DSI_IRQn); NVIC_DisableIRQ(DSI_IRQn);
} }
void display_pixeldata(uint16_t c) { void display_pixeldata(uint16_t c) {

View File

@ -40,8 +40,8 @@ void hash_processor_init(void) {
DMA_Handle.Parent = &hhash; DMA_Handle.Parent = &hhash;
HAL_NVIC_SetPriority(GPDMA1_Channel12_IRQn, IRQ_PRI_DMA, 0); NVIC_SetPriority(GPDMA1_Channel12_IRQn, IRQ_PRI_NORMAL);
HAL_NVIC_EnableIRQ(GPDMA1_Channel12_IRQn); NVIC_EnableIRQ(GPDMA1_Channel12_IRQn);
} }
void GPDMA1_Channel12_IRQHandler(void) { HAL_DMA_IRQHandler(&DMA_Handle); } void GPDMA1_Channel12_IRQHandler(void) { HAL_DMA_IRQHandler(&DMA_Handle); }

View File

@ -138,7 +138,7 @@ void HAL_SD_MspInit(SD_HandleTypeDef *hsd) {
SDMMC_CLK_ENABLE(); SDMMC_CLK_ENABLE();
// NVIC configuration for SDIO interrupts // NVIC configuration for SDIO interrupts
svc_setpriority(SDMMC_IRQn, IRQ_PRI_SDIO); svc_setpriority(SDMMC_IRQn, IRQ_PRI_NORMAL);
svc_enableIRQ(SDMMC_IRQn); svc_enableIRQ(SDMMC_IRQn);
} }

View File

@ -192,9 +192,8 @@ extern "C" {
* @brief This is the HAL system configuration section * @brief This is the HAL system configuration section
*/ */
#define VDD_VALUE 3300UL /*!< Value of VDD in mv */ #define VDD_VALUE 3300UL /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY \ #define TICK_INT_PRIORITY 0UL /*!< tick interrupt priority */
(15UL) /*!< tick interrupt priority (lowest by default) */
#define USE_RTOS 0U #define USE_RTOS 0U
#define PREFETCH_ENABLE 1U /*!< Enable prefetch */ #define PREFETCH_ENABLE 1U /*!< Enable prefetch */
@ -554,7 +553,8 @@ extern "C" {
*/ */
#define assert_param(expr) \ #define assert_param(expr) \
((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */ /* Exported functions
------------------------------------------------------- */
void assert_failed(uint8_t *file, uint32_t line); void assert_failed(uint8_t *file, uint32_t line);
#else #else
#define assert_param(expr) ((void)0U) #define assert_param(expr) ((void)0U)

View File

@ -227,7 +227,7 @@ void tamper_init(void) {
TAMP_IER_ITAMP11IE | TAMP_IER_ITAMP12IE | TAMP_IER_ITAMP13IE; TAMP_IER_ITAMP11IE | TAMP_IER_ITAMP12IE | TAMP_IER_ITAMP13IE;
// Enable TAMP interrupt at NVIC controller // Enable TAMP interrupt at NVIC controller
NVIC_SetPriority(TAMP_IRQn, IRQ_PRI_TAMP); NVIC_SetPriority(TAMP_IRQn, IRQ_PRI_HIGHEST);
NVIC_EnableIRQ(TAMP_IRQn); NVIC_EnableIRQ(TAMP_IRQn);
} }

View File

@ -2,6 +2,7 @@
#include TREZOR_BOARD #include TREZOR_BOARD
#include "i2c.h" #include "i2c.h"
#include "irq.h"
/** @addtogroup STM32U5x9J_DISCOVERY /** @addtogroup STM32U5x9J_DISCOVERY
* @{ * @{
@ -823,8 +824,8 @@ int32_t BSP_TS_EnableIT(uint32_t Instance) {
HAL_GPIO_Init(TS_INT_GPIO_PORT, &gpio_init_structure); HAL_GPIO_Init(TS_INT_GPIO_PORT, &gpio_init_structure);
/* Enable and set Touch screen EXTI Interrupt to the lowest priority */ /* Enable and set Touch screen EXTI Interrupt to the lowest priority */
HAL_NVIC_SetPriority((IRQn_Type)(TS_INT_EXTI_IRQn), 0x0F, 0x00); NVIC_SetPriority((IRQn_Type)(TS_INT_EXTI_IRQn), IRQ_PRI_NORMAL);
HAL_NVIC_EnableIRQ((IRQn_Type)(TS_INT_EXTI_IRQn)); NVIC_EnableIRQ((IRQn_Type)(TS_INT_EXTI_IRQn));
return BSP_ERROR_NONE; return BSP_ERROR_NONE;
} }

View File

@ -20,6 +20,7 @@
#include <trustzone.h> #include <trustzone.h>
#include STM32_HAL_H #include STM32_HAL_H
#include "irq.h"
#ifdef BOARDLOADER #ifdef BOARDLOADER
@ -142,8 +143,8 @@ void trustzone_init_boardloader(void) {
HAL_GTZC_TZIC_EnableIT(GTZC_PERIPH_ALL); HAL_GTZC_TZIC_EnableIT(GTZC_PERIPH_ALL);
// Enable GTZC secure interrupt // Enable GTZC secure interrupt
HAL_NVIC_SetPriority(GTZC_IRQn, 0, 0); // Highest priority level NVIC_SetPriority(GTZC_IRQn, IRQ_PRI_HIGHEST);
HAL_NVIC_EnableIRQ(GTZC_IRQn); NVIC_EnableIRQ(GTZC_IRQn);
} }
#endif // BOARDLOADER #endif // BOARDLOADER

View File

@ -66,6 +66,7 @@
#include STM32_HAL_H #include STM32_HAL_H
#include "display_internal.h" #include "display_internal.h"
#include "irq.h"
/* Common Error codes */ /* Common Error codes */
#define BSP_ERROR_NONE 0 #define BSP_ERROR_NONE 0
@ -86,15 +87,6 @@
#define BSP_BUTTON_USER_IT_PRIORITY \ #define BSP_BUTTON_USER_IT_PRIORITY \
0x0FUL /* Default is lowest priority level */ 0x0FUL /* Default is lowest priority level */
/* LCD interrupt priorities */
#define BSP_LCD_GFXMMU_IT_PRIORITY \
0x0FUL /* Default is lowest priority level \
*/
#define BSP_LCD_LTDC_IT_PRIORITY 0x0FUL /* Default is lowest priority level */
#define BSP_LCD_DSI_IT_PRIORITY 0x0FUL /* Default is lowest priority level */
/* HSPI RAM interrupt priority */
#define BSP_HSPI_RAM_IT_PRIORITY 0x0FUL /* Default is lowest priority level */
#define LCD_PIXEL_FORMAT_ARGB8888 \ #define LCD_PIXEL_FORMAT_ARGB8888 \
0x00000000U /*!< ARGB8888 LTDC pixel format \ 0x00000000U /*!< ARGB8888 LTDC pixel format \
*/ */
@ -1336,8 +1328,8 @@ static void GFXMMU_MspInit(GFXMMU_HandleTypeDef *hgfxmmu) {
__HAL_RCC_GFXMMU_CLK_ENABLE(); __HAL_RCC_GFXMMU_CLK_ENABLE();
/* Enable GFXMMU interrupt */ /* Enable GFXMMU interrupt */
HAL_NVIC_SetPriority(GFXMMU_IRQn, BSP_LCD_GFXMMU_IT_PRIORITY, 0); NVIC_SetPriority(GFXMMU_IRQn, IRQ_PRI_NORMAL);
HAL_NVIC_EnableIRQ(GFXMMU_IRQn); NVIC_EnableIRQ(GFXMMU_IRQn);
} }
/** /**
@ -1350,7 +1342,7 @@ static void GFXMMU_MspDeInit(GFXMMU_HandleTypeDef *hgfxmmu) {
UNUSED(hgfxmmu); UNUSED(hgfxmmu);
/* Disable GFXMMU interrupt */ /* Disable GFXMMU interrupt */
HAL_NVIC_DisableIRQ(GFXMMU_IRQn); NVIC_DisableIRQ(GFXMMU_IRQn);
/* GFXMMU clock disable */ /* GFXMMU clock disable */
__HAL_RCC_GFXMMU_CLK_DISABLE(); __HAL_RCC_GFXMMU_CLK_DISABLE();
@ -1369,11 +1361,11 @@ static void LTDC_MspInit(LTDC_HandleTypeDef *hltdc) {
__HAL_RCC_LTDC_CLK_ENABLE(); __HAL_RCC_LTDC_CLK_ENABLE();
/* Enable LTDC interrupt */ /* Enable LTDC interrupt */
HAL_NVIC_SetPriority(LTDC_IRQn, BSP_LCD_LTDC_IT_PRIORITY, 0); NVIC_SetPriority(LTDC_IRQn, IRQ_PRI_NORMAL);
HAL_NVIC_EnableIRQ(LTDC_IRQn); NVIC_EnableIRQ(LTDC_IRQn);
HAL_NVIC_SetPriority(LTDC_ER_IRQn, BSP_LCD_LTDC_IT_PRIORITY, 0); NVIC_SetPriority(LTDC_ER_IRQn, IRQ_PRI_NORMAL);
HAL_NVIC_EnableIRQ(LTDC_ER_IRQn); NVIC_EnableIRQ(LTDC_ER_IRQn);
} }
/** /**
@ -1386,8 +1378,8 @@ static void LTDC_MspDeInit(LTDC_HandleTypeDef *hltdc) {
UNUSED(hltdc); UNUSED(hltdc);
/* Disable LTDC interrupts */ /* Disable LTDC interrupts */
HAL_NVIC_DisableIRQ(LTDC_ER_IRQn); NVIC_DisableIRQ(LTDC_ER_IRQn);
HAL_NVIC_DisableIRQ(LTDC_IRQn); NVIC_DisableIRQ(LTDC_IRQn);
/* LTDC clock disable */ /* LTDC clock disable */
__HAL_RCC_LTDC_CLK_DISABLE(); __HAL_RCC_LTDC_CLK_DISABLE();
@ -1494,8 +1486,8 @@ static void DSI_MspInit(DSI_HandleTypeDef *hdsi) {
/* Enable DSI NVIC interrupt */ /* Enable DSI NVIC interrupt */
/* Default is lowest priority level */ /* Default is lowest priority level */
HAL_NVIC_SetPriority(DSI_IRQn, 0x0FUL, 0); NVIC_SetPriority(DSI_IRQn, IRQ_PRI_NORMAL);
HAL_NVIC_EnableIRQ(DSI_IRQn); NVIC_EnableIRQ(DSI_IRQn);
} }
/** /**
@ -1530,7 +1522,7 @@ static void DSI_MspDeInit(DSI_HandleTypeDef *hdsi) {
__HAL_RCC_DSI_RELEASE_RESET(); __HAL_RCC_DSI_RELEASE_RESET();
/* Disable DSI interrupts */ /* Disable DSI interrupts */
HAL_NVIC_DisableIRQ(DSI_IRQn); NVIC_DisableIRQ(DSI_IRQn);
} }
int32_t BSP_LCD_SetFrameBuffer(uint32_t Instance, uint32_t fb_addr) { int32_t BSP_LCD_SetFrameBuffer(uint32_t Instance, uint32_t fb_addr) {