Browse Source

HAL_ChibiOS: add a max quota of GPIO interrupts

This implements a max quota of GPIO interrupts per 100ms period to
prevent high interrupt counts from consuming all CPU and causing a
lockup. The limit is set as 10k interrupts per 0.1s period. That limit
should be high enough for all reasonable uses of GPIO interrupt
handlers while being below the level that causes significant CPU loads
and flight issues

This addresses issue #15384
zr-v5.1
Andrew Tridgell 4 years ago
parent
commit
e471b23f58
  1. 45
      libraries/AP_HAL_ChibiOS/GPIO.cpp
  2. 5
      libraries/AP_HAL_ChibiOS/GPIO.h
  3. 5
      libraries/AP_HAL_ChibiOS/Scheduler.cpp

45
libraries/AP_HAL_ChibiOS/GPIO.cpp

@ -18,6 +18,10 @@
#include <AP_BoardConfig/AP_BoardConfig.h> #include <AP_BoardConfig/AP_BoardConfig.h>
#include "hwdef/common/stm32_util.h" #include "hwdef/common/stm32_util.h"
#include <AP_InternalError/AP_InternalError.h>
#ifndef HAL_NO_UARTDRIVER
#include <GCS_MAVLink/GCS.h>
#endif
using namespace ChibiOS; using namespace ChibiOS;
@ -31,6 +35,7 @@ static struct gpio_entry {
bool is_input; bool is_input;
uint8_t mode; uint8_t mode;
thread_reference_t thd_wait; thread_reference_t thd_wait;
uint16_t isr_quota;
} _gpio_tab[] = HAL_GPIO_PINS; } _gpio_tab[] = HAL_GPIO_PINS;
#define NUM_PINS ARRAY_SIZE(_gpio_tab) #define NUM_PINS ARRAY_SIZE(_gpio_tab)
@ -313,6 +318,21 @@ static void pal_interrupt_cb_functor(void *arg)
if (!(g->fn)) { if (!(g->fn)) {
return; return;
} }
if (g->isr_quota >= 1) {
/*
we have an interrupt quota enabled for this pin. If the
quota remaining drops to 1 without it being refreshed in
timer_tick then we disable the interrupt source. This is to
prevent CPU overload due to very high GPIO interrupt counts
*/
if (g->isr_quota == 1) {
osalSysLockFromISR();
palDisableLineEventI(g->pal_line);
osalSysUnlockFromISR();
return;
}
g->isr_quota--;
}
(g->fn)(g->pin_num, palReadLine(g->pal_line), now); (g->fn)(g->pin_num, palReadLine(g->pal_line), now);
} }
@ -366,3 +386,28 @@ bool GPIO::wait_pin(uint8_t pin, INTERRUPT_TRIGGER_TYPE mode, uint32_t timeout_u
return msg == MSG_OK; return msg == MSG_OK;
} }
#ifndef IOMCU_FW
/*
timer to setup interrupt quotas for a 100ms period from
monitor thread
*/
void GPIO::timer_tick()
{
// allow 100k interrupts/second max for GPIO interrupt sources, which is
// 10k per 100ms call to timer_tick()
const uint16_t quota = 10000U;
for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
if (_gpio_tab[i].isr_quota == 1) {
// we ran out of ISR quota for this pin since the last
// check. This is not really an internal error, but we use
// INTERNAL_ERROR() to get the reporting mechanism
#ifndef HAL_NO_UARTDRIVER
GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"ISR flood on pin %u", _gpio_tab[i].pin_num);
#endif
INTERNAL_ERROR(AP_InternalError::error_t::gpio_isr);
}
_gpio_tab[i].isr_quota = quota;
}
}
#endif // IOMCU_FW

5
libraries/AP_HAL_ChibiOS/GPIO.h

@ -61,6 +61,11 @@ public:
forever. Return true on pin change, false on timeout forever. Return true on pin change, false on timeout
*/ */
bool wait_pin(uint8_t pin, INTERRUPT_TRIGGER_TYPE mode, uint32_t timeout_us) override; bool wait_pin(uint8_t pin, INTERRUPT_TRIGGER_TYPE mode, uint32_t timeout_us) override;
#ifndef IOMCU_FW
// timer tick
void timer_tick(void) override;
#endif
private: private:
bool _usb_connected; bool _usb_connected;

5
libraries/AP_HAL_ChibiOS/Scheduler.cpp

@ -19,6 +19,7 @@
#include "AP_HAL_ChibiOS.h" #include "AP_HAL_ChibiOS.h"
#include "Scheduler.h" #include "Scheduler.h"
#include "Util.h" #include "Util.h"
#include "GPIO.h"
#include <AP_HAL_ChibiOS/UARTDriver.h> #include <AP_HAL_ChibiOS/UARTDriver.h>
#include <AP_HAL_ChibiOS/AnalogIn.h> #include <AP_HAL_ChibiOS/AnalogIn.h>
@ -415,6 +416,10 @@ void Scheduler::_monitor_thread(void *arg)
} }
#endif // HAL_NO_LOGGING #endif // HAL_NO_LOGGING
#ifndef IOMCU_FW
// setup GPIO interrupt quotas
hal.gpio->timer_tick();
#endif
} }
} }
#endif // HAL_NO_MONITOR_THREAD #endif // HAL_NO_MONITOR_THREAD

Loading…
Cancel
Save