AP_Compass: remove misleading message

Not having data ready during initialization is normal. Don't print error
message since it can mislead people to think the compass was not
initialized successfully.
This commit is contained in:
Lucas De Marchi 2016-03-18 20:57:36 -03:00
parent 1d1d224c18
commit a671b7f5b2

View File

@ -317,9 +317,6 @@ AP_Compass_LSM303D::init()
if (_data_ready()) {
_spi_sem->give();
break;
} else {
hal.console->println(
"LSM303D startup failed: no data ready");
}
_spi_sem->give();
}