diff --git a/libraries/AP_Compass/AP_Compass_AK09916.cpp b/libraries/AP_Compass/AP_Compass_AK09916.cpp index b844a1abdf..946c661c84 100644 --- a/libraries/AP_Compass/AP_Compass_AK09916.cpp +++ b/libraries/AP_Compass/AP_Compass_AK09916.cpp @@ -201,7 +201,6 @@ bool AP_Compass_AK09916::init() } if (!_reset()) { - hal.console->printf("AK09916: Reset Failed\n"); goto fail; } diff --git a/libraries/AP_Compass/AP_Compass_AK8963.cpp b/libraries/AP_Compass/AP_Compass_AK8963.cpp index a7e7f93f75..9128396cb5 100644 --- a/libraries/AP_Compass/AP_Compass_AK8963.cpp +++ b/libraries/AP_Compass/AP_Compass_AK8963.cpp @@ -123,7 +123,6 @@ bool AP_Compass_AK8963::init() AP_HAL::Semaphore *bus_sem = _bus->get_semaphore(); if (!bus_sem) { - hal.console->printf("AK8963: Unable to get bus semaphore\n"); return false; } _bus->get_semaphore()->take_blocking(); diff --git a/libraries/AP_Compass/AP_Compass_LSM303D.cpp b/libraries/AP_Compass/AP_Compass_LSM303D.cpp index 3eb8cde8a0..6199bf78c5 100644 --- a/libraries/AP_Compass/AP_Compass_LSM303D.cpp +++ b/libraries/AP_Compass/AP_Compass_LSM303D.cpp @@ -290,7 +290,6 @@ bool AP_Compass_LSM303D::_hardware_init() // Test WHOAMI uint8_t whoami = _register_read(ADDR_WHO_AM_I); if (whoami != WHO_I_AM) { - hal.console->printf("LSM303D: unexpected WHOAMI 0x%x\n", (unsigned)whoami); goto fail_whoami; }