Browse Source

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.
mission-4.1.18
Lucas De Marchi 6 years ago committed by Lucas De Marchi
parent
commit
e66de36016
  1. 2
      libraries/AP_HAL_ChibiOS/I2CDevice.cpp

2
libraries/AP_HAL_ChibiOS/I2CDevice.cpp

@ -269,7 +269,7 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len, @@ -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…
Cancel
Save