added ground_course in proper 0-360 degrees * 100 for Ardupilot

git-svn-id: https://arducopter.googlecode.com/svn/trunk@348 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2010-08-30 00:09:47 +00:00
parent cf7eefd94b
commit 2ca8ac7259
2 changed files with 2 additions and 0 deletions

View File

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

View File

@ -13,6 +13,7 @@ class Compass
int16_t mag_X;
int16_t mag_Y;
int16_t mag_Z;
int32_t ground_course;
float heading;
float heading_X;
float heading_Y;