ArduCopter: compass init never fails
This commit is contained in:
parent
f8be4efed4
commit
6d87b9316f
@ -92,7 +92,8 @@ void Copter::init_compass()
|
||||
return;
|
||||
}
|
||||
|
||||
if (!compass.init() || !compass.read()) {
|
||||
compass.init();
|
||||
if (!compass.read()) {
|
||||
// make sure we don't pass a broken compass to DCM
|
||||
hal.console->printf("COMPASS INIT ERROR\n");
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_COMPASS,ERROR_CODE_FAILED_TO_INITIALISE);
|
||||
|
Loading…
Reference in New Issue
Block a user