From 20626a1fe1ff11dd4820f4b59bd387876f48a971 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 27 Mar 2019 18:02:12 +1100 Subject: [PATCH] Plane: move automatic declination setting into AP_Compass itself --- ArduPlane/ArduPlane.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 32a0ae6b95..0fe08ad0ae 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -379,11 +379,6 @@ void Plane::update_GPS_10Hz(void) next_WP_loc = prev_WP_loc = home; - if (AP::compass().enabled()) { - // Set compass declination automatically - const Location &loc = gps.location(); - compass.set_initial_location(loc.lat, loc.lng); - } ground_start_count = 0; } }