Rover: don't override declination on startup

This commit is contained in:
Andrew Tridgell 2013-02-22 07:14:54 +11:00
parent 06ccf8495b
commit 882f058e7d
1 changed files with 0 additions and 1 deletions

View File

@ -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 ) {