mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed brick2 valid status in POWR flags for fmuv5
and fixed sense of VBUS
This commit is contained in:
parent
0501d52c2a
commit
d58bb700a3
|
@ -356,12 +356,21 @@ void AnalogIn::update_power_flags(void)
|
||||||
if (!palReadLine(HAL_GPIO_PIN_VDD_SERVO_VALID)) {
|
if (!palReadLine(HAL_GPIO_PIN_VDD_SERVO_VALID)) {
|
||||||
flags |= MAV_POWER_STATUS_SERVO_VALID;
|
flags |= MAV_POWER_STATUS_SERVO_VALID;
|
||||||
}
|
}
|
||||||
|
#elif defined(HAL_GPIO_PIN_VDD_BRICK2_VALID)
|
||||||
|
// some boards defined BRICK2 instead of servo valid
|
||||||
|
if (!palReadLine(HAL_GPIO_PIN_VDD_BRICK2_VALID)) {
|
||||||
|
flags |= MAV_POWER_STATUS_SERVO_VALID;
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_GPIO_PIN_VBUS
|
#ifdef HAL_GPIO_PIN_VBUS
|
||||||
if (palReadLine(HAL_GPIO_PIN_VBUS)) {
|
if (palReadLine(HAL_GPIO_PIN_VBUS)) {
|
||||||
flags |= MAV_POWER_STATUS_USB_CONNECTED;
|
flags |= MAV_POWER_STATUS_USB_CONNECTED;
|
||||||
}
|
}
|
||||||
|
#elif defined(HAL_GPIO_PIN_nVBUS)
|
||||||
|
if (!palReadLine(HAL_GPIO_PIN_nVBUS)) {
|
||||||
|
flags |= MAV_POWER_STATUS_USB_CONNECTED;
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_GPIO_PIN_VDD_5V_HIPOWER_OC
|
#ifdef HAL_GPIO_PIN_VDD_5V_HIPOWER_OC
|
||||||
|
|
|
@ -220,7 +220,7 @@ define HAL_HEATER_GPIO_PIN 80
|
||||||
|
|
||||||
PG1 VDD_BRICK_VALID INPUT PULLUP
|
PG1 VDD_BRICK_VALID INPUT PULLUP
|
||||||
PG2 VDD_BRICK2_VALID INPUT PULLUP
|
PG2 VDD_BRICK2_VALID INPUT PULLUP
|
||||||
PG3 VBUS INPUT
|
PG3 nVBUS INPUT PULLUP
|
||||||
PF13 VDD_5V_HIPOWER_OC INPUT PULLUP
|
PF13 VDD_5V_HIPOWER_OC INPUT PULLUP
|
||||||
PE15 VDD_5V_PERIPH_OC INPUT PULLUP
|
PE15 VDD_5V_PERIPH_OC INPUT PULLUP
|
||||||
PB10 nSPI5_RESET_EXTERNAL1 OUTPUT HIGH
|
PB10 nSPI5_RESET_EXTERNAL1 OUTPUT HIGH
|
||||||
|
|
Loading…
Reference in New Issue