mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
HAL_ChibiOS: move the power control changes to be only CubeBlack
This aims to fix #11455. I have been unable to reproduce the issue, which leaves me thinking it is either a bootloader difference or a hw difference between pixhawk1 clones and real pixhawk1 boards
This commit is contained in:
parent
df4fc0fff0
commit
51e187342b
@ -10,3 +10,7 @@ USB_PRODUCT 0x1001
|
||||
USB_STRING_MANUFACTURER "Hex/ProfiCNC"
|
||||
USB_STRING_PRODUCT "CubeBlack-BL"
|
||||
USB_STRING_SERIAL "%SERIAL%"
|
||||
|
||||
# disable peripheral and sensor power in the bootloader
|
||||
PA8 nVDD_5V_PERIPH_EN OUTPUT HIGH
|
||||
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
|
||||
|
@ -55,3 +55,17 @@ COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90
|
||||
|
||||
# also probe for external compasses
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
|
||||
# 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()
|
||||
undef PA8
|
||||
PA8 nVDD_5V_PERIPH_EN OUTPUT HIGH
|
||||
|
||||
# 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 LOW on startup, which
|
||||
# means sensors off, then it is pulled HIGH in peripheral_power_enable()
|
||||
undef PE3
|
||||
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
|
||||
|
@ -85,7 +85,3 @@ 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,11 +213,10 @@ PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PA7 SPI1_MOSI SPI1
|
||||
|
||||
# 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 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 is the pin that senses USB being connected. It is an input pin
|
||||
# setup as OPENDRAIN.
|
||||
@ -366,9 +365,8 @@ 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 LOW on startup, which
|
||||
# means sensors off, then it is pulled HIGH in peripheral_power_enable()
|
||||
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
|
||||
# timing affecting sensor stability. We pull it high by default.
|
||||
PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH
|
||||
|
||||
# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters).
|
||||
PE7 UART7_RX UART7
|
||||
|
Loading…
Reference in New Issue
Block a user