mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: removed IST8310 overrun message
this is not useful and just causes concern to users. Any small bus delay can trigger this. We have health monitoring at a higher level
This commit is contained in:
parent
db22aaad50
commit
1f4ca97605
|
@ -200,10 +200,6 @@ void AP_Compass_IST8308::timer()
|
|||
return;
|
||||
}
|
||||
|
||||
if (stat & STAT1_VAL_DOR) {
|
||||
printf("IST8308: data overrun\n");
|
||||
}
|
||||
|
||||
if (!_dev->read_registers(DATAX_L_REG, (uint8_t *) &buffer,
|
||||
sizeof(buffer))) {
|
||||
return;
|
||||
|
|
Loading…
Reference in New Issue