From 19d2195ea3041d965e8671f12e294a7f70497892 Mon Sep 17 00:00:00 2001 From: "tridge60@gmail.com" Date: Wed, 10 Aug 2011 12:52:53 +0000 Subject: [PATCH] compass: set the orientation of compass before compass.init() the compass.init() code uses the orientation when calculating the calibration. We need to use the right orientation. git-svn-id: https://arducopter.googlecode.com/svn/trunk@3071 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/system.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopterMega/system.pde b/ArduCopterMega/system.pde index d9caffbcfb..348d048068 100644 --- a/ArduCopterMega/system.pde +++ b/ArduCopterMega/system.pde @@ -453,9 +453,9 @@ static void resetPerfData(void) { static void init_compass() { + compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft dcm.set_compass(&compass); bool junkbool = compass.init(); - compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft Vector3f junkvector = compass.get_offsets(); // load offsets to account for airframe magnetic interference }