mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
HAL_ChibiOS: disable peripheral power on boot on fmuv3
then enable after 100ms, and let settle for 20ms. This is to fix an issue with peripheral power on consistency with all fmuv3 boards Thanks to Philip for the suggestion
This commit is contained in:
parent
0a5d6a430a
commit
6333494d99
@ -291,6 +291,10 @@ void peripheral_power_enable(void)
|
||||
// others need it active high
|
||||
palWriteLine(HAL_GPIO_PIN_VDD_3V3_SD_CARD_EN, 1);
|
||||
#endif
|
||||
for (i=0; i<20; i++) {
|
||||
// give 20ms for sensors to settle
|
||||
chThdSleep(chTimeMS2I(1));
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -85,3 +85,7 @@ define HAL_STORAGE_SIZE 16384
|
||||
# define CH_DBG_ENABLE_CHECKS TRUE
|
||||
# define CH_DBG_SYSTEM_STATE_CHECK TRUE
|
||||
# define CH_DBG_ENABLE_STACK_CHECK TRUE
|
||||
|
||||
# disable peripheral and sensor power in the bootloader
|
||||
PA8 nVDD_5V_PERIPH_EN OUTPUT HIGH
|
||||
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
|
||||
|
@ -213,10 +213,11 @@ PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PA7 SPI1_MOSI SPI1
|
||||
|
||||
# This defines an output pin which will default to output LOW. It is a
|
||||
# pin that enables peripheral power on this board.
|
||||
|
||||
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.
|
||||
@ -365,8 +366,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
|
||||
|
Loading…
Reference in New Issue
Block a user