HAL_ChibiOS: update power VALID pins

This commit is contained in:
Andrew Tridgell 2020-02-13 19:06:12 +11:00
parent 863807c9fb
commit 571fbf8f71
11 changed files with 45 additions and 45 deletions

View File

@ -212,11 +212,11 @@ PA8 HEATER_EN OUTPUT LOW GPIO(80)
define HAL_HEATER_GPIO_PIN 80
define HAL_HAVE_IMU_HEATER 1
PG1 VDD_BRICK_VALID INPUT PULLUP
PG2 VDD_BRICK2_VALID INPUT PULLUP
PG0 nVBUS INPUT PULLUP
PJ3 VDD_5V_HIPOWER_OC INPUT PULLUP
PJ4 VDD_5V_PERIPH_OC INPUT PULLUP
PG1 VDD_BRICK_nVALID INPUT PULLUP
PG2 VDD_BRICK2_nVALID INPUT PULLUP
PG0 VBUS_nVALID INPUT PULLUP
PJ3 VDD_5V_HIPOWER_nOC INPUT PULLUP
PJ4 VDD_5V_PERIPH_nOC INPUT PULLUP
PB10 nSPI5_RESET_EXTERNAL1 OUTPUT HIGH
# SPI devices

View File

@ -96,7 +96,7 @@ PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
# This input pin is used to detect that power is valid on USB.
PC0 VBUS_VALID INPUT
PC0 VBUS_nVALID INPUT PULLUP
# This defines the CS pin for the magnetometer and first IMU. Note
# that CS pins are software controlled, and are not tied to a particular
@ -203,10 +203,10 @@ PE12 FMU_LED_AMBER OUTPUT HIGH OPENDRAIN GPIO(0)
# Power flag pins: these tell the MCU the status of the various power
# supplies that are available. The pin names need to exactly match the
# names used in AnalogIn.cpp.
PB5 VDD_BRICK_VALID INPUT PULLUP
PB7 VDD_SERVO_VALID INPUT PULLUP
PE10 VDD_5V_HIPOWER_OC INPUT PULLUP
PE15 VDD_5V_PERIPH_OC INPUT PULLUP
PB5 VDD_BRICK_nVALID INPUT PULLUP
PB7 VDD_BRICK2_nVALID INPUT PULLUP
PE10 VDD_5V_HIPOWER_nOC INPUT PULLUP
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP
SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ
SPIDEV ms5611_ext SPI4 DEVID2 BARO_EXT_CS MODE3 20*MHZ 20*MHZ

View File

@ -226,7 +226,7 @@ PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
# this input pin is used to detect that power is valid on USB
PC0 VBUS_VALID INPUT
PC0 VBUS_nVALID INPUT PULLUP
# this defines the CS pin for the magnetometer and first IMU. Note
# that CS pins are software controlled, and are not tied to a particular
@ -331,10 +331,10 @@ PE12 FMU_LED_AMBER OUTPUT GPIO(0)
# power flag pins. These tell the MCU the status of the various power
# supplies that are available. The pin names need to exactly match the
# names used in AnalogIn.cpp.
PB5 VDD_BRICK_VALID INPUT PULLUP
PB7 VDD_SERVO_VALID INPUT PULLUP
PE10 VDD_5V_HIPOWER_OC INPUT PULLUP
PE15 VDD_5V_PERIPH_OC INPUT PULLUP
PB5 VDD_BRICK_nVALID INPUT PULLUP
PB7 VDD_BRICK2_nVALID INPUT PULLUP
PE10 VDD_5V_HIPOWER_nOC INPUT PULLUP
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP
# now the SPI device table. This table creates all accessible SPI
# devices, giving the name of the device (which is used by device

View File

@ -122,7 +122,7 @@ PB13 CAN2_TX CAN2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
PC0 VBUS_VALID INPUT
PC0 VBUS_nVALID INPUT PULLUP
PC1 BATT2_VOLTAGE_SENS ADC1 SCALE(1)
PC3 BATT2_CURRENT_SENS ADC1 SCALE(1)
#PC4 SAFETY_IN INPUT PULLDOWN
@ -196,10 +196,10 @@ PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
# Power flag pins: these tell the MCU the status of the various power
# supplies that are available. The pin names need to exactly match the
# names used in AnalogIn.cpp.
PB5 VDD_BRICK_VALID INPUT PULLUP
PG5 VDD_BRICK2_VALID INPUT PULLUP
PF3 VDD_5V_HIPOWER_OC INPUT PULLUP
PG4 VDD_5V_PERIPH_OC INPUT PULLUP
PB5 VDD_BRICK_nVALID INPUT PULLUP
PG5 VDD_BRICK2_nVALID INPUT PULLUP
PF3 VDD_5V_HIPOWER_nOC INPUT PULLUP
PG4 VDD_5V_PERIPH_nOC INPUT PULLUP
# SPI device table
SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ

View File

@ -231,11 +231,11 @@ define HAL_IMU_TEMP_DEFAULT 45
# SPI temperature sensor
PH5 TSENSE_CS CS
PG1 VDD_BRICK_VALID INPUT PULLUP
PG2 VDD_BRICK2_VALID INPUT PULLUP
PG1 VDD_BRICK_nVALID INPUT PULLUP
PG2 VDD_BRICK2_nVALID INPUT PULLUP
PA9 VBUS INPUT
PF13 VDD_5V_HIPOWER_OC INPUT PULLUP
PE15 VDD_5V_PERIPH_OC INPUT PULLUP
PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP
PB10 nSPI5_RESET_EXTERNAL1 OUTPUT HIGH
# capture pins

View File

@ -265,7 +265,7 @@ PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
# This input pin is used to detect that power is valid on USB.
PC0 VBUS_VALID INPUT
PC0 VBUS_nVALID INPUT PULLUP
# This defines the CS pin for the magnetometer and first IMU. Note
# that CS pins are software controlled, and are not tied to a particular
@ -373,10 +373,10 @@ PE12 FMU_LED_AMBER OUTPUT HIGH OPENDRAIN GPIO(0)
# Power flag pins: these tell the MCU the status of the various power
# supplies that are available. The pin names need to exactly match the
# names used in AnalogIn.cpp.
PB5 VDD_BRICK_VALID INPUT PULLUP
PB7 VDD_SERVO_VALID INPUT PULLUP
PE10 VDD_5V_HIPOWER_OC INPUT PULLUP
PE15 VDD_5V_PERIPH_OC INPUT PULLUP
PB5 VDD_BRICK_nVALID INPUT PULLUP
PB7 VDD_BRICK2_nVALID INPUT PULLUP
PE10 VDD_5V_HIPOWER_nOC INPUT PULLUP
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP
# Now the SPI device table. This table creates all accessible SPI
# devices, giving the name of the device (which is used by device

View File

@ -70,7 +70,7 @@ PB0 SPEKTRUM_RC INPUT PULLUP GPIO(71)
define HAL_GPIO_SPEKTRUM_RC 71
PB2 BOOT1 INPUT
PB5 VDD_BRICK_VALID INPUT
PB5 VDD_BRICK_VALID INPUT PULLDOWN
# USART1 is ESP8266
PB6 USART1_TX USART1
@ -96,7 +96,7 @@ PB13 CAN2_TX CAN2 # this is SPI2_SCK on beta board
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
PC0 VBUS_VALID INPUT
PC0 VBUS_VALID INPUT PULLDOWN
PC1 RSSI_IN ADC1
PC2 MPU9250_CS CS
PC3 LED_SAFETY OUTPUT

View File

@ -226,11 +226,11 @@ PH4 GPIO_CAN3_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(72)
PA7 HEATER_EN OUTPUT LOW GPIO(80)
define HAL_HEATER_GPIO_PIN 80
PG1 VDD_BRICK_VALID INPUT PULLUP
PG2 VDD_BRICK2_VALID INPUT PULLUP
PG3 nVBUS INPUT PULLUP
PF13 VDD_5V_HIPOWER_OC INPUT PULLUP
PE15 VDD_5V_PERIPH_OC INPUT PULLUP
PG1 VDD_BRICK_nVALID INPUT PULLUP
PG2 VDD_BRICK2_nVALID INPUT PULLUP
PG3 VBUS_nVALID INPUT PULLUP
PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP
PB10 nSPI5_RESET_EXTERNAL1 OUTPUT HIGH
# capture pins

View File

@ -130,7 +130,7 @@ PF9 SPI5_MOSI SPI5
PA9 VBUS INPUT OPENDRAIN
# This input pin is used to detect that power is valid on USB.
PC0 VBUS_VALID INPUT
PC0 VBUS_VALID INPUT PULLDOWN
# Now we define the pins that USB is connected on.
PA11 OTG_FS_DM OTG1
@ -213,7 +213,7 @@ PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH
# Power flag pins: these tell the MCU the status of the various power
# supplies that are available. The pin names need to exactly match the
# names used in AnalogIn.cpp.
PB5 VDD_BRICK_VALID INPUT PULLUP
PB5 VDD_BRICK_nVALID INPUT PULLUP
SPIDEV dps310 SPI2 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ
SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ

View File

@ -228,7 +228,7 @@ PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
# this input pin is used to detect that power is valid on USB
PC0 VBUS_VALID INPUT
PC0 VBUS_VALID INPUT PULLDOWN
# this defines the CS pin for the magnetometer and first IMU. Note
# that CS pins are software controlled, and are not tied to a particular
@ -330,10 +330,10 @@ PE12 FMU_LED_AMBER OUTPUT GPIO(0)
# power flag pins. These tell the MCU the status of the various power
# supplies that are available. The pin names need to exactly match the
# names used in AnalogIn.cpp.
PB5 VDD_BRICK_VALID INPUT PULLUP
# PB7 VDD_SERVO_VALID INPUT PULLUP #Not Connected
# PE10 VDD_5V_HIPOWER_OC INPUT PULLUP #Not Connected
PE15 VDD_5V_PERIPH_OC INPUT PULLUP
PB5 VDD_BRICK_nVALID INPUT PULLUP
# PB7 VDD_BRICK2_nVALID INPUT PULLUP #Not Connected
# PE10 VDD_5V_HIPOWER_nOC INPUT PULLUP #Not Connected
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP
# now the SPI device table. This table creates all accessible SPI
# devices, giving the name of the device (which is used by device

View File

@ -52,7 +52,7 @@ PA15 TIM2_CH1 TIM2 GPIO(77) ALARM
PB0 TIM3_CH3 TIM3 PPMIN # RC Input PPM
PB2 BOOT1 INPUT
PB5 VDD_BRICK_VALID INPUT
PB5 VDD_BRICK_VALID INPUT PULLDOWN
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1
@ -64,7 +64,7 @@ PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
PC0 VBUS_VALID INPUT
PC0 VBUS_VALID INPUT PULLDOWN
PC1 RSSI_IN ADC1
PC2 LPS22HB_CS CS
PC3 LED_SAFETY OUTPUT