mirror of https://github.com/ArduPilot/ardupilot
I2C:: catch some more types of I2C errors for error count
This commit is contained in:
parent
8c2dadc12f
commit
27ff999319
|
@ -31,13 +31,8 @@
|
||||||
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <inttypes.h>
|
#include <AP_Common.h>
|
||||||
#include "I2C.h"
|
#include "I2C.h"
|
||||||
#if defined(ARDUINO) && ARDUINO >= 100
|
|
||||||
#include "Arduino.h"
|
|
||||||
#else
|
|
||||||
#include "WProgram.h"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -392,32 +387,56 @@ uint8_t I2C::read(uint8_t address, uint8_t registerAddress, uint8_t numberBytes,
|
||||||
nack = numberBytes - 1;
|
nack = numberBytes - 1;
|
||||||
returnStatus = 0;
|
returnStatus = 0;
|
||||||
returnStatus = start();
|
returnStatus = start();
|
||||||
if(returnStatus) {return(returnStatus); }
|
if (returnStatus) {
|
||||||
|
_lockup_count++;
|
||||||
|
return(returnStatus);
|
||||||
|
}
|
||||||
returnStatus = sendAddress(SLA_W(address));
|
returnStatus = sendAddress(SLA_W(address));
|
||||||
if(returnStatus) {return(returnStatus); }
|
if(returnStatus) {
|
||||||
|
_lockup_count++;
|
||||||
|
return(returnStatus);
|
||||||
|
}
|
||||||
returnStatus = sendByte(registerAddress);
|
returnStatus = sendByte(registerAddress);
|
||||||
if(returnStatus) {return(returnStatus); }
|
if(returnStatus) {
|
||||||
|
_lockup_count++;
|
||||||
|
return(returnStatus);
|
||||||
|
}
|
||||||
returnStatus = start();
|
returnStatus = start();
|
||||||
if(returnStatus) {return(returnStatus); }
|
if(returnStatus) {
|
||||||
|
_lockup_count++;
|
||||||
|
return(returnStatus);
|
||||||
|
}
|
||||||
returnStatus = sendAddress(SLA_R(address));
|
returnStatus = sendAddress(SLA_R(address));
|
||||||
if(returnStatus) {return(returnStatus); }
|
if(returnStatus) {
|
||||||
|
_lockup_count++;
|
||||||
|
return(returnStatus);
|
||||||
|
}
|
||||||
for(uint8_t i = 0; i < numberBytes; i++)
|
for(uint8_t i = 0; i < numberBytes; i++)
|
||||||
{
|
{
|
||||||
if( i == nack )
|
if( i == nack )
|
||||||
{
|
{
|
||||||
returnStatus = receiveByte(0);
|
returnStatus = receiveByte(0);
|
||||||
if(returnStatus != MR_DATA_NACK) {return(returnStatus); }
|
if (returnStatus != MR_DATA_NACK) {
|
||||||
|
_lockup_count++;
|
||||||
|
return(returnStatus);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
returnStatus = receiveByte(1);
|
returnStatus = receiveByte(1);
|
||||||
if(returnStatus != MR_DATA_ACK) {return(returnStatus); }
|
if (returnStatus != MR_DATA_ACK) {
|
||||||
|
_lockup_count++;
|
||||||
|
return(returnStatus);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
dataBuffer[i] = TWDR;
|
dataBuffer[i] = TWDR;
|
||||||
bytesAvailable = i+1;
|
bytesAvailable = i+1;
|
||||||
totalBytes = i+1;
|
totalBytes = i+1;
|
||||||
}
|
}
|
||||||
returnStatus = stop();
|
returnStatus = stop();
|
||||||
|
if (returnStatus) {
|
||||||
|
_lockup_count++;
|
||||||
|
}
|
||||||
return(returnStatus);
|
return(returnStatus);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue