hwdef: CubeOrange: do power reset on peripherals and sensor at boot

This commit is contained in:
bugobliterator 2020-09-13 21:16:29 +05:30 committed by Andrew Tridgell
parent a2ee82d8d9
commit 575a56a6b6
2 changed files with 12 additions and 3 deletions

View File

@ -56,3 +56,7 @@ PC15 ACCEL_EXT_CS CS
PD7 BARO_CS CS
PE4 MPU_EXT_CS CS
PD10 FRAM_CS CS SPEED_VERYLOW
# disable peripheral and sensor power in the bootloader
PA8 nVDD_5V_PERIPH_EN OUTPUT HIGH
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW

View File

@ -51,7 +51,11 @@ PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
PA8 VDD_5V_PERIPH_EN OUTPUT LOW
# This defines an output pin which will default to output HIGH. It is
# a pin that enables peripheral power on this board. It starts in the
# off state, then is pulled low to enable peripherals in
# peripheral_power_enable()
PA8 nVDD_5V_PERIPH_EN OUTPUT HIGH
# This is the pin that senses USB being connected. It is an input pin
# setup as OPENDRAIN.
@ -190,8 +194,9 @@ PE6 SPI4_MOSI SPI4
# This is the pin to enable the sensors rail. It can be used to power
# cycle sensors to recover them in case there are problems with power on
# timing affecting sensor stability. We pull it high by default.
PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH
# timing affecting sensor stability. We pull it LOW on startup, which
# means sensors off, then it is pulled HIGH in peripheral_power_enable()
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters).
PE7 UART7_RX UART7