mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
HAL_ChibiOS: fix I2C transaction without stop condition
Start using i2cSoftStop() instead of i2cStop() so the peripheral continues to be enabled and with non-gated clock. This allows time for the I2C peripheral to continue the ack or stop.
This commit is contained in:
parent
e51f0bc7ff
commit
e66de36016
@ -269,7 +269,7 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
|
||||
recv, recv_len, chTimeMS2I(timeout_ms));
|
||||
}
|
||||
|
||||
i2cStop(I2CD[bus.busnum].i2c);
|
||||
i2cSoftStop(I2CD[bus.busnum].i2c);
|
||||
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_STOP, "i2cStart state");
|
||||
|
||||
bus.dma_handle->unlock();
|
||||
|
Loading…
Reference in New Issue
Block a user