Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

HAL_ChibiOS: add a max quota of GPIO interrupts #15388

Merged
merged 3 commits into from Oct 1, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
3 changes: 3 additions & 0 deletions libraries/AP_HAL/GPIO.h
Expand Up @@ -98,4 +98,7 @@ class AP_HAL::GPIO {

/* return true if USB cable is connected */
virtual bool usb_connected(void) = 0;

// optional timer tick
virtual void timer_tick(void) {};
};
45 changes: 45 additions & 0 deletions libraries/AP_HAL_ChibiOS/GPIO.cpp
Expand Up @@ -18,6 +18,10 @@

#include <AP_BoardConfig/AP_BoardConfig.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;

Expand All @@ -31,6 +35,7 @@ static struct gpio_entry {
bool is_input;
uint8_t mode;
thread_reference_t thd_wait;
uint16_t isr_quota;
} _gpio_tab[] = HAL_GPIO_PINS;

#define NUM_PINS ARRAY_SIZE(_gpio_tab)
Expand Down Expand Up @@ -313,6 +318,21 @@ static void pal_interrupt_cb_functor(void *arg)
if (!(g->fn)) {
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);
}

Expand Down Expand Up @@ -366,3 +386,28 @@ bool GPIO::wait_pin(uint8_t pin, INTERRUPT_TRIGGER_TYPE mode, uint32_t timeout_u

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) {
tridge marked this conversation as resolved.
Show resolved Hide resolved
// 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);
tridge marked this conversation as resolved.
Show resolved Hide resolved
}
_gpio_tab[i].isr_quota = quota;
}
}
#endif // IOMCU_FW
5 changes: 5 additions & 0 deletions libraries/AP_HAL_ChibiOS/GPIO.h
Expand Up @@ -61,6 +61,11 @@ class ChibiOS::GPIO : public AP_HAL::GPIO {
forever. Return true on pin change, false on timeout
*/
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:
bool _usb_connected;
Expand Down
5 changes: 5 additions & 0 deletions libraries/AP_HAL_ChibiOS/Scheduler.cpp
Expand Up @@ -19,6 +19,7 @@
#include "AP_HAL_ChibiOS.h"
#include "Scheduler.h"
#include "Util.h"
#include "GPIO.h"

#include <AP_HAL_ChibiOS/UARTDriver.h>
#include <AP_HAL_ChibiOS/AnalogIn.h>
Expand Down Expand Up @@ -415,6 +416,10 @@ void Scheduler::_monitor_thread(void *arg)
}
#endif // HAL_NO_LOGGING

#ifndef IOMCU_FW
// setup GPIO interrupt quotas
hal.gpio->timer_tick();
#endif
}
}
#endif // HAL_NO_MONITOR_THREAD
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_InternalError/AP_InternalError.cpp
Expand Up @@ -55,6 +55,7 @@ void AP_InternalError::errors_as_string(uint8_t *buffer, const uint16_t len) con
"bad_rotation",
"stack_ovrflw", // stack_overflow
"imu_reset", // imu_reset
"gpio_isr",
};

static_assert((1U<<(ARRAY_SIZE(error_bit_descriptions))) == uint32_t(AP_InternalError::error_t::__LAST__), "too few descriptions for bits");
Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_InternalError/AP_InternalError.h
Expand Up @@ -62,7 +62,8 @@ class AP_InternalError {
bad_rotation = (1U << 22), //0x400000 4194304
stack_overflow = (1U << 23), //0x800000 8388608
imu_reset = (1U << 24), //0x1000000 16777216
__LAST__ = (1U << 25), // used only for sanity check
gpio_isr = (1U << 25), //0x2000000 33554432
__LAST__ = (1U << 26), // used only for sanity check
};

// if you've changed __LAST__ to be 32, then you will want to
Expand Down