added ground_course 0-36000 for Ardupilot

git-svn-id: https://arducopter.googlecode.com/svn/trunk@353 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2010-08-30 00:18:56 +00:00
parent a8b995ae1a
commit 11ccbb9ed7
2 changed files with 3 additions and 3 deletions

View File

@ -107,7 +107,7 @@ AP_Compass::calculate(float roll, float pitch)
// Magnetic heading
heading = atan2(-head_Y, head_X);
ground_course = degrees(heading) + 180;
ground_course = (degrees(heading) + 180) * 100;
// Optimization for external DCM use. calculate normalized components
heading_X = cos(heading);

View File

@ -28,13 +28,13 @@ void loop()
compass.update();
compass.calculate(0, 0); // roll = 0, pitch = 0 for this example
Serial.print("Heading:");
Serial.print(degrees(compass.heading));
Serial.print(compass.ground_course,DEC);
Serial.print(" (");
Serial.print(compass.mag_X);
Serial.print(",");
Serial.print(compass.mag_Y);
Serial.print(",");
Serial.print(compass.mag_Z);
Serial.println();
Serial.println(" )");
}
}