|
|
|
@ -16,8 +16,10 @@ env OPTIMIZE -Os
@@ -16,8 +16,10 @@ env OPTIMIZE -Os
|
|
|
|
|
# bootloader takes first sector |
|
|
|
|
FLASH_RESERVE_START_KB 128 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
# ChibiOS system timer |
|
|
|
|
STM32_ST_USE_TIMER 5 |
|
|
|
|
STM32_ST_USE_TIMER 12 |
|
|
|
|
define CH_CFG_ST_RESOLUTION 16 |
|
|
|
|
|
|
|
|
|
# USB |
|
|
|
|
PA11 OTG_FS_DM OTG1 |
|
|
|
@ -143,10 +145,10 @@ PD3 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70)
@@ -143,10 +145,10 @@ PD3 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70)
|
|
|
|
|
# Motors |
|
|
|
|
PB0 TIM8_CH2N TIM8 PWM(1) GPIO(50) |
|
|
|
|
PB1 TIM8_CH3N TIM8 PWM(2) GPIO(51) |
|
|
|
|
PA0 TIM2_CH1 TIM2 PWM(3) GPIO(52) |
|
|
|
|
PA1 TIM2_CH2 TIM2 PWM(4) GPIO(53) |
|
|
|
|
PA2 TIM2_CH3 TIM2 PWM(5) GPIO(54) |
|
|
|
|
PA3 TIM2_CH4 TIM2 PWM(6) GPIO(55) |
|
|
|
|
PA0 TIM5_CH1 TIM5 PWM(3) GPIO(52) |
|
|
|
|
PA1 TIM5_CH2 TIM5 PWM(4) GPIO(53) |
|
|
|
|
PA2 TIM5_CH3 TIM5 PWM(5) GPIO(54) |
|
|
|
|
PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55) |
|
|
|
|
PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) |
|
|
|
|
PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57) |
|
|
|
|
PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) |
|
|
|
@ -156,10 +158,7 @@ PE6 TIM15_CH2 TIM15 PWM(12) GPIO(61)
@@ -156,10 +158,7 @@ PE6 TIM15_CH2 TIM15 PWM(12) GPIO(61)
|
|
|
|
|
PA8 TIM1_CH1 TIM1 PWM(13) GPIO(62) # for WS2812 LED |
|
|
|
|
|
|
|
|
|
# Beeper |
|
|
|
|
PA15 BUZZER OUTPUT GPIO(32) LOW |
|
|
|
|
define HAL_BUZZER_PIN 32 |
|
|
|
|
define HAL_BUZZER_ON 1 |
|
|
|
|
define HAL_BUZZER_OFF 0 |
|
|
|
|
PA15 TIM2_CH1 TIM2 GPIO(32) ALARM |
|
|
|
|
|
|
|
|
|
# microSD support |
|
|
|
|
PC8 SDMMC1_D0 SDMMC1 |
|
|
|
|