mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed build without ISR limit
This commit is contained in:
parent
97c56c068e
commit
b30f3697d2
|
@ -284,8 +284,10 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef STM32_I2C_ISR_LIMIT
|
||||||
AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
|
AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
|
||||||
pd.i2c_isr_count += I2CD[bus.busnum].i2c->isr_count;
|
pd.i2c_isr_count += I2CD[bus.busnum].i2c->isr_count;
|
||||||
|
#endif
|
||||||
|
|
||||||
if (ret == MSG_OK) {
|
if (ret == MSG_OK) {
|
||||||
bus.bouncebuffer_finish(send, recv, recv_len);
|
bus.bouncebuffer_finish(send, recv, recv_len);
|
||||||
|
|
Loading…
Reference in New Issue