mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
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:
parent
1d1d224c18
commit
a671b7f5b2
@ -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();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user