diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AIRLink/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/AIRLink/hwdef.dat index 7de3644c2e..be9ce9f633 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AIRLink/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/AIRLink/hwdef.dat @@ -83,8 +83,12 @@ PD15 VDD_3V3_SENSORS2_EN OUTPUT HIGH PE7 VDD_3V3_SENSORS3_EN OUTPUT HIGH PG8 VDD_3V3_SENSORS4_EN OUTPUT HIGH +# enable peripherals power pin PF12 VDD_5V_HIPOWER_EN OUTPUT HIGH +# enable LTE module power pin +PG4 VDD_3V5_LTE_EN OUTPUT HIGH + # drdy pins PF2 DRDY4_ICM20602 INPUT PH12 MPU_FPC_DRDY INPUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c index 95050f33cf..aa85c75d33 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c @@ -298,7 +298,7 @@ void get_rtc_backup(uint8_t idx, uint32_t *v, uint8_t n) */ void peripheral_power_enable(void) { -#if defined(HAL_GPIO_PIN_nVDD_5V_PERIPH_EN) || defined(HAL_GPIO_PIN_nVDD_5V_HIPOWER_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SENSORS_EN)|| defined(HAL_GPIO_PIN_VDD_3V3_SENSORS2_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SENSORS3_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SENSORS4_EN) || defined(HAL_GPIO_PIN_nVDD_3V3_SD_CARD_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SD_CARD_EN) +#if defined(HAL_GPIO_PIN_nVDD_5V_PERIPH_EN) || defined(HAL_GPIO_PIN_nVDD_5V_HIPOWER_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SENSORS_EN)|| defined(HAL_GPIO_PIN_VDD_3V3_SENSORS2_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SENSORS3_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SENSORS4_EN) || defined(HAL_GPIO_PIN_nVDD_3V3_SD_CARD_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SD_CARD_EN) || defined(HAL_GPIO_PIN_VDD_3V5_LTE_EN) // we don't know what state the bootloader had the CTS pin in, so // wait here with it pulled up from the PAL table for enough time // for the radio to be definately powered down @@ -336,6 +336,9 @@ void peripheral_power_enable(void) #ifdef HAL_GPIO_PIN_VDD_3V3_SD_CARD_EN // others need it active high palWriteLine(HAL_GPIO_PIN_VDD_3V3_SD_CARD_EN, 1); +#endif +#ifdef HAL_GPIO_PIN_VDD_3V5_LTE_EN + palWriteLine(HAL_GPIO_PIN_VDD_3V5_LTE_EN, 1); #endif for (i=0; i<20; i++) { // give 20ms for sensors to settle