From 1476f044e6e75c368df55ef8550db6fe7a780350 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 1 Mar 2012 15:21:13 +1100 Subject: [PATCH] I2C: added lockup_count() interface used for reporting I2C problems --- libraries/I2C/I2C.cpp | 6 ++++++ libraries/I2C/I2C.h | 3 +++ 2 files changed, 9 insertions(+) diff --git a/libraries/I2C/I2C.cpp b/libraries/I2C/I2C.cpp index 2b699b8cc8..254670138f 100644 --- a/libraries/I2C/I2C.cpp +++ b/libraries/I2C/I2C.cpp @@ -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) diff --git a/libraries/I2C/I2C.h b/libraries/I2C/I2C.h index ca957312ad..0400b39e03 100644 --- a/libraries/I2C/I2C.h +++ b/libraries/I2C/I2C.h @@ -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;