Hi,
I have a problem with I2C in ChibiOS that might be related to this, if not I can open a new topic.
I am communicating over I2C with a custom device, that applies very long clock stretching (varying from 3-20ms) in a small fraction of its packets. In some cases, this has lead to a locked i2c bus for us.
I have investigated using a logic analyser, and found that the following happens in ChibiOS:
(1) Master sends a READ command to slave.
(2) Slave holds the clock for some time (likely to process some data before sending it).
(3) After some time, releases the SCL line and starts transmitting data correctly.
(4) In the middle of the transfer, the master determines that the transfer is taking too long (i2cMasterReceiveTimeout() called in AP_HAL_ChibiOS/I2CDevice.cpp returns MSG_TIMEOUT), aborts the transfer and stops cycling the clock.
(5) In the unfortunate case where the last transmitted bit happens to be a 0, the slave holds the SDA line low (active). The slave does not time out (!) so it keeps the line low, as it is still trying to finish transferring the data and is waiting for the next clock cycle. The low SDA is preventing the master from sending a new START condition,
This results in an unusable I2C bus.
In Nuttx, the problem did not present itself as clearly to us, since the master (AP) does not appear to time out there, allowing to slave to finish its transfer of the delayed data and leaving the bus in a clean state.
To emulate the NuttX behaviour, I tried to increase the timeout value of the i2c device in ardupilot, which seemed to have no effect. I even replaced the last argument of i2cMasterReceiveTimeout in I2CDevice.cpp to TIME_INFINITE (found in the ChibiOS documentation), but the transfer seems to time out anyway after about 3 or 4 ms, I don’t know why.
Until we make the slave behave a bit nicer, is there a way to call an i2c reset (by cycling the clock) from within ardupilot, or increase the timeout?
I am building arducopter from the master branch, and am using a pixhawk2.
Attached (below) is a file with the logic analyzer captures in both Nuttx, and ChibiOS.
In the case of Nuttx, the packet of interest is the 4th. For ChibiOS, the packet of interest is the 8th.
Thanks a lot for any advice! If any more information is required I’d be happy to provide it.
Logic Analyzer i2c.zip (24.7 KB)