Skip to content

Commit

Permalink
AP_HAL_ChibiOS: Add more quota for 1024 wire motor encoder
Browse files Browse the repository at this point in the history
  • Loading branch information
lida2003 committed Jun 10, 2024
1 parent 5d9c84c commit a316e78
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/GPIO.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -601,7 +601,7 @@ void GPIO::timer_tick()
// allow 100k interrupts/second max for GPIO interrupt sources, which is
// 10k per 100ms call to timer_tick()
#if HAVE_GPIO_PINS
const uint16_t quota = 10000U;
const uint16_t quota = 60000U;
for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
if (_gpio_tab[i].isr_quota != 1) {
// Reset quota for next tick
Expand Down

0 comments on commit a316e78

Please sign in to comment.