From 882f058e7d61e8ebb2e3def94bf26f632878e108 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 22 Feb 2013 07:14:54 +1100 Subject: [PATCH] Rover: don't override declination on startup --- APMrover2/system.pde | 1 - 1 file changed, 1 deletion(-) diff --git a/APMrover2/system.pde b/APMrover2/system.pde index 2c32aa95b5..2bb402f927 100644 --- a/APMrover2/system.pde +++ b/APMrover2/system.pde @@ -192,7 +192,6 @@ static void init_ardupilot() 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_declination(ToRad(0.0)); // set local difference between magnetic north and true north cliSerial->print("Compass auto-detected as: "); switch( compass.product_id ) {