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
This commit is contained in:
tridge60@gmail.com 2011-08-10 12:52:53 +00:00
parent 2995878e99
commit 19d2195ea3
1 changed files with 1 additions and 1 deletions

View File

@ -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
}