diff --git a/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde b/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde index cac77edd72..247bb728d6 100644 --- a/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde +++ b/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde @@ -55,28 +55,6 @@ void setup() { compass.set_and_save_offsets(0,0,0,0); // set offsets to account for surrounding interference compass.set_declination(ToRad(0.0)); // set local difference between magnetic north and true north - hal.console->print("Compass auto-detected as: "); - switch( compass.product_id ) { - case AP_COMPASS_TYPE_HIL: - hal.console->println("HIL"); - break; - case AP_COMPASS_TYPE_HMC5843: - hal.console->println("HMC5843"); - break; - case AP_COMPASS_TYPE_HMC5883L: - hal.console->println("HMC5883L"); - break; - case AP_COMPASS_TYPE_PX4: - hal.console->println("PX4"); - break; - case AP_COMPASS_TYPE_AK8963_MPU9250: - hal.console->println("AK8963"); - break; - default: - hal.console->println("unknown"); - break; - } - hal.scheduler->delay(1000); timer = hal.scheduler->micros(); }