I2C: added lockup_count() interface

used for reporting I2C problems
This commit is contained in:
Andrew Tridgell 2012-03-01 15:21:13 +11:00
parent c9031f1d36
commit 1476f044e6
2 changed files with 9 additions and 0 deletions

View File

@ -536,6 +536,12 @@ void I2C::lockUp()
{
TWCR = 0; //releases SDA and SCL lines to high impedance
TWCR = _BV(TWEN) | _BV(TWIE) | _BV(TWEA); //reinitialize TWI
_lockup_count++;
}
uint8_t I2C::lockup_count(void)
{
return _lockup_count;
}
SIGNAL(TWI_vect)

View File

@ -97,6 +97,7 @@ class I2C
uint8_t read(uint8_t, uint8_t, uint8_t*);
uint8_t read(uint8_t, uint8_t, uint8_t, uint8_t*);
uint8_t receive();
uint8_t lockup_count();
private:
uint8_t start();
@ -108,6 +109,8 @@ class I2C
uint8_t returnStatus;
uint8_t nack;
uint8_t data[MAX_BUFFER_SIZE];
uint8_t _lockup_count;
static uint8_t bytesAvailable;
static uint8_t bufferIndex;
static uint8_t totalBytes;