fixed SITL GPS heading to be 0..360

This commit is contained in:
Andrew Tridgell 2012-02-14 10:46:26 +11:00
parent c9b432955d
commit f95d7cadc5
1 changed files with 3 additions and 0 deletions

View File

@ -146,6 +146,9 @@ void sitl_update_gps(double latitude, double longitude, float altitude,
velned.speed_3d = velned.speed_2d;
lon_scale = cos(ToRad(latitude));
velned.heading_2d = ToDeg(atan2(lon_scale*speedE, speedN)) * 100000.0;
if (velned.heading_2d < 0.0) {
velned.heading_2d += 360.0 * 100000.0;
}
velned.speed_accuracy = 2;
velned.heading_accuracy = 4;