mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 15:33:57 -04:00
HAL_ChibiOS: added ISR limit on I2C
this will prevent any possibility of an I2C interrupt storm. This is designed to address the most likely cause of #11642
This commit is contained in:
parent
b8602abdeb
commit
f8cfbb8062
@ -22,6 +22,7 @@
|
|||||||
|
|
||||||
#include "Scheduler.h"
|
#include "Scheduler.h"
|
||||||
#include "hwdef/common/stm32_util.h"
|
#include "hwdef/common/stm32_util.h"
|
||||||
|
#include <AP_InternalError/AP_InternalError.h>
|
||||||
|
|
||||||
#include "ch.h"
|
#include "ch.h"
|
||||||
#include "hal.h"
|
#include "hal.h"
|
||||||
@ -274,6 +275,11 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
|
|||||||
|
|
||||||
bus.dma_handle->unlock();
|
bus.dma_handle->unlock();
|
||||||
|
|
||||||
|
if (I2CD[bus.busnum].i2c->errors & I2C_ISR_LIMIT) {
|
||||||
|
AP::internalerror().error(AP_InternalError::error_t::i2c_isr);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
if (ret == MSG_OK) {
|
if (ret == MSG_OK) {
|
||||||
bus.bouncebuffer_finish(send, recv, recv_len);
|
bus.bouncebuffer_finish(send, recv, recv_len);
|
||||||
i2cReleaseBus(I2CD[bus.busnum].i2c);
|
i2cReleaseBus(I2CD[bus.busnum].i2c);
|
||||||
|
@ -382,3 +382,8 @@
|
|||||||
* WDG driver system settings.
|
* WDG driver system settings.
|
||||||
*/
|
*/
|
||||||
#define STM32_WDG_USE_IWDG FALSE
|
#define STM32_WDG_USE_IWDG FALSE
|
||||||
|
|
||||||
|
// limit ISR count per byte
|
||||||
|
#define STM32_I2C_ISR_LIMIT 6
|
||||||
|
|
||||||
|
|
||||||
|
@ -439,3 +439,6 @@
|
|||||||
#define STM32_WDG_USE_IWDG FALSE
|
#define STM32_WDG_USE_IWDG FALSE
|
||||||
|
|
||||||
#define STM32_EXTI_ENHANCED
|
#define STM32_EXTI_ENHANCED
|
||||||
|
|
||||||
|
// limit ISR count per byte
|
||||||
|
#define STM32_I2C_ISR_LIMIT 6
|
||||||
|
Loading…
Reference in New Issue
Block a user