AP_Compass: print I2C error count in test sketch

This commit is contained in:
Andrew Tridgell 2012-11-12 10:28:06 +11:00
parent 321d40f73a
commit 8c2dadc12f

View File

@ -99,11 +99,12 @@ void loop()
offset[2] = -(max[2]+min[2])/2; offset[2] = -(max[2]+min[2])/2;
// display all to user // display all to user
Serial.printf("Heading: %.2f (%3u,%3u,%3u) ", Serial.printf("Heading: %.2f (%3u,%3u,%3u) I2cerr=%u ",
ToDeg(heading), ToDeg(heading),
compass.mag_x, compass.mag_x,
compass.mag_y, compass.mag_y,
compass.mag_z); compass.mag_z,
I2c.lockup_count());
// display offsets // display offsets
Serial.printf("\t offsets(%.2f, %.2f, %.2f)", Serial.printf("\t offsets(%.2f, %.2f, %.2f)",