mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 15:48:29 -04:00
AP_Compass: fixed example
This commit is contained in:
parent
0bafd33cfa
commit
f4455d063e
@ -55,28 +55,6 @@ void setup() {
|
|||||||
compass.set_and_save_offsets(0,0,0,0); // set offsets to account for surrounding interference
|
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
|
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);
|
hal.scheduler->delay(1000);
|
||||||
timer = hal.scheduler->micros();
|
timer = hal.scheduler->micros();
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user