HAL_ChibiOS: set pwm select pins high for 3.3V PWMout on startup

This commit is contained in:
Siddharth Purohit 2019-04-01 13:46:01 +05:30 committed by Andrew Tridgell
parent 051842ea34
commit 7b54103271
4 changed files with 8 additions and 2 deletions

View File

@ -38,6 +38,9 @@ UART_ORDER OTG1 UART7
PE7 UART7_RX UART7
PE8 UART7_TX UART7
# Pin for PWM Voltage Selection
PB4 PWM_VOLT_SEL OUTPUT HIGH
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

View File

@ -171,7 +171,7 @@ PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
define BOARD_PWM_COUNT_DEFAULT 4
# Pin for PWM Voltage Selection
PB4 PWM_VOLT_SEL OUTPUT GPIO(3)
PB4 PWM_VOLT_SEL OUTPUT HIGH GPIO(3)
# Relays default to use GPIO pins 54 and 55.
define RELAY1_PIN_DEFAULT 54

View File

@ -48,6 +48,9 @@ PD12 USART3_RTS USART3
PE7 UART7_RX UART7
PE8 UART7_TX UART7
# Pin for PWM Voltage Selection
PB4 PWM_VOLT_SEL OUTPUT HIGH
# now we define the pins that USB is connected on
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

View File

@ -310,7 +310,7 @@ PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
# Pin for PWM Voltage Selection
PB4 PWM_VOLT_SEL OUTPUT GPIO(3)
PB4 PWM_VOLT_SEL OUTPUT HIGH GPIO(3)
# this is the invensense data-ready pin. We don't use it in the
# default driver