mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
HAL_ChibiOS: retain OPENDRAIN if set on a pin
this allows OPENDRAIN when set on a pin to be retained when set with a pinMode(). This fixes a partially lit B/E LED on the Pixhawk4
This commit is contained in:
parent
ffe642a530
commit
096a624301
@ -17,6 +17,7 @@
|
|||||||
#include "GPIO.h"
|
#include "GPIO.h"
|
||||||
|
|
||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
|
#include "hwdef/common/stm32_util.h"
|
||||||
|
|
||||||
using namespace ChibiOS;
|
using namespace ChibiOS;
|
||||||
|
|
||||||
@ -79,6 +80,15 @@ void GPIO::pinMode(uint8_t pin, uint8_t output)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
g->mode = output?PAL_MODE_OUTPUT_PUSHPULL:PAL_MODE_INPUT;
|
g->mode = output?PAL_MODE_OUTPUT_PUSHPULL:PAL_MODE_INPUT;
|
||||||
|
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4)
|
||||||
|
if (g->mode == PAL_MODE_OUTPUT_PUSHPULL) {
|
||||||
|
// retain OPENDRAIN if already set
|
||||||
|
iomode_t old_mode = palReadLineMode(g->pal_line);
|
||||||
|
if ((old_mode & PAL_MODE_OUTPUT_OPENDRAIN) == PAL_MODE_OUTPUT_OPENDRAIN) {
|
||||||
|
g->mode = PAL_MODE_OUTPUT_OPENDRAIN;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
palSetLineMode(g->pal_line, g->mode);
|
palSetLineMode(g->pal_line, g->mode);
|
||||||
g->is_input = !output;
|
g->is_input = !output;
|
||||||
}
|
}
|
||||||
|
@ -290,7 +290,7 @@ PC12 SDMMC_CK SDMMC1
|
|||||||
PD2 SDMMC_CMD SDMMC1
|
PD2 SDMMC_CMD SDMMC1
|
||||||
|
|
||||||
# red LED marked as B/E
|
# red LED marked as B/E
|
||||||
PB1 LED_RED OUTPUT GPIO(90)
|
PB1 LED_RED OUTPUT OPENDRAIN GPIO(90)
|
||||||
|
|
||||||
# green LED marked as PWR. We leave this solid on, but allow
|
# green LED marked as PWR. We leave this solid on, but allow
|
||||||
# for it to be controlled as a relay if needed
|
# for it to be controlled as a relay if needed
|
||||||
|
Loading…
Reference in New Issue
Block a user