Browse Source

AP_RPM: set pin to input before attaching interrupt

this fixes input on AUX6 on CubeBlack
master
Andrew Tridgell 6 years ago
parent
commit
e862c349e8
  1. 1
      libraries/AP_RPM/RPM_Pin.cpp

1
libraries/AP_RPM/RPM_Pin.cpp

@ -60,6 +60,7 @@ void AP_RPM_Pin::update(void) @@ -60,6 +60,7 @@ void AP_RPM_Pin::update(void)
// attach to new pin
last_pin = get_pin();
if (last_pin) {
hal.gpio->pinMode(last_pin, HAL_GPIO_INPUT);
if (!hal.gpio->attach_interrupt(
last_pin,
FUNCTOR_BIND_MEMBER(&AP_RPM_Pin::irq_handler, void, uint8_t, bool, uint32_t),

Loading…
Cancel
Save