mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: default to timer 5 for H7
This commit is contained in:
parent
dcc038dc83
commit
37bcd6e7d8
|
@ -430,7 +430,9 @@
|
|||
* ST driver system settings.
|
||||
*/
|
||||
#define STM32_ST_IRQ_PRIORITY 8
|
||||
#define STM32_ST_USE_TIMER 2
|
||||
#ifndef STM32_ST_USE_TIMER
|
||||
#define STM32_ST_USE_TIMER 5
|
||||
#endif
|
||||
|
||||
/*
|
||||
* UART driver system settings.
|
||||
|
|
Loading…
Reference in New Issue