mirror of https://github.com/ArduPilot/ardupilot
Rover: don't override declination on startup
This commit is contained in:
parent
06ccf8495b
commit
882f058e7d
|
@ -192,7 +192,6 @@ static void init_ardupilot()
|
||||||
|
|
||||||
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft.
|
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft.
|
||||||
compass.set_offsets(0,0,0); // set offsets to account for surrounding interference
|
compass.set_offsets(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
|
|
||||||
|
|
||||||
cliSerial->print("Compass auto-detected as: ");
|
cliSerial->print("Compass auto-detected as: ");
|
||||||
switch( compass.product_id ) {
|
switch( compass.product_id ) {
|
||||||
|
|
Loading…
Reference in New Issue