HAL_ChibiOS: adjust Pixhawk4Pro VBUS and DMA priority

This commit is contained in:
Andrew Tridgell 2019-03-02 20:16:48 +11:00
parent 54cb76ca83
commit 6f07d804b9

View File

@ -234,7 +234,7 @@ define HAL_HEATER_GPIO_PIN 80
PG1 VDD_BRICK_VALID INPUT PULLUP
PG2 VDD_BRICK2_VALID INPUT PULLUP
PG3 VBUS INPUT
PA9 VBUS INPUT
PF13 VDD_5V_HIPOWER_OC INPUT PULLUP
PE15 VDD_5V_PERIPH_OC INPUT PULLUP
PB10 nSPI5_RESET_EXTERNAL1 OUTPUT HIGH
@ -324,6 +324,8 @@ ROMFS io_firmware.bin Tools/IO_Firmware/fmuv2_IO.bin
# don't share IOMCU DMA
DMA_NOSHARE UART8* SPI1* TIM*UP*
DMA_PRIORITY UART8* ADC* SPI1*
# battery setup
define HAL_BATT_MONITOR_DEFAULT 4
define HAL_BATT_VOLT_PIN 16