mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
hwdef: disable power reset on peripheral line
This commit is contained in:
parent
86f9c4e83f
commit
225bd15855
@ -57,3 +57,4 @@ PD10 FRAM_CS CS SPEED_VERYLOW
|
||||
|
||||
# disable peripheral and sensor power in the bootloader
|
||||
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
|
||||
PA8 nVDD_5V_PERIPH_EN OUTPUT LOW
|
||||
|
@ -54,7 +54,7 @@ PA7 SPI1_MOSI SPI1
|
||||
# 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
|
||||
PA8 nVDD_5V_PERIPH_EN OUTPUT LOW
|
||||
|
||||
# This is the pin that senses USB being connected. It is an input pin
|
||||
# setup as OPENDRAIN.
|
||||
|
Loading…
Reference in New Issue
Block a user