AP_HAL_ESP32: I2CDevice: take into account driver timeout

Necessary for proper INA3221 operation apparently.
This commit is contained in:
Thomas Watson 2025-02-10 16:25:05 -06:00 committed by Peter Barker
parent 34a0e827fd
commit de2ebe22b6
2 changed files with 6 additions and 4 deletions

View File

@ -61,7 +61,8 @@ I2CDeviceManager::I2CDeviceManager(void)
I2CDevice::I2CDevice(uint8_t busnum, uint8_t address, uint32_t bus_clock, bool use_smbus, uint32_t timeout_ms) :
bus(I2CDeviceManager::businfo[busnum]),
_retries(10),
_address(address)
_address(address),
_timeout_ms(timeout_ms)
{
set_device_bus(busnum);
set_device_address(address);
@ -118,9 +119,10 @@ bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
}
i2c_master_stop(cmd);
TickType_t timeout = 1 + 16L * (send_len + recv_len) * 1000 / bus.bus_clock / portTICK_PERIOD_MS;
uint32_t timeout_ms = 1 + 16L * (send_len + recv_len) * 1000 / bus.bus_clock;
timeout_ms = MAX(timeout_ms, _timeout_ms);
for (int i = 0; !result && i < _retries; i++) {
result = (i2c_master_cmd_begin(bus.port, cmd, timeout) == ESP_OK);
result = (i2c_master_cmd_begin(bus.port, cmd, pdMS_TO_TICKS(timeout_ms)) == ESP_OK);
if (!result) {
i2c_reset_tx_fifo(bus.port);
i2c_reset_rx_fifo(bus.port);

View File

@ -106,7 +106,7 @@ protected:
uint8_t _retries;
uint8_t _address;
char *pname;
uint32_t _timeout_ms;
};
class I2CDeviceManager : public AP_HAL::I2CDeviceManager