From b350b07593bbf2f2889b96feaa361e355fe605c2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 25 Mar 2018 21:43:42 +1100 Subject: [PATCH] HAL_ChibiOS: allow internal GPIO fuctions to use disabled pins --- libraries/AP_HAL_ChibiOS/GPIO.cpp | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/GPIO.cpp b/libraries/AP_HAL_ChibiOS/GPIO.cpp index 60167c0fde..802bb053e4 100644 --- a/libraries/AP_HAL_ChibiOS/GPIO.cpp +++ b/libraries/AP_HAL_ChibiOS/GPIO.cpp @@ -36,11 +36,11 @@ static struct gpio_entry { /* map a user pin number to a GPIO table entry */ -static struct gpio_entry *gpio_by_pin_num(uint8_t pin_num) +static struct gpio_entry *gpio_by_pin_num(uint8_t pin_num, bool check_enabled=true) { for (uint8_t i=0; ipal_line); if (p && ext_irq[pad] != nullptr && ext_irq[pad] != p) { // already used - hal.console->printf("A fail\n"); return false; } else if (!p && !ext_irq[pad]) { // nothing to remove - hal.console->printf("D fail\n"); return false; } uint32_t chmode = 0; @@ -209,7 +207,7 @@ void ext_interrupt_cb(EXTDriver *extp, expchannel_t channel) */ void GPIO::_set_mode(uint8_t pin, uint32_t mode) { - struct gpio_entry *g = gpio_by_pin_num(pin); + struct gpio_entry *g = gpio_by_pin_num(pin, false); if (g) { palSetLineMode(g->pal_line, mode); }