Plane: Use AHRS for heading in mode loiter

This commit is contained in:
Rishabh 2020-04-08 13:09:31 +05:30 committed by Andrew Tridgell
parent ff112a726b
commit 6989cb0131
1 changed files with 1 additions and 1 deletions

View File

@ -52,7 +52,7 @@ bool ModeLoiter::isHeadingLinedUp_cd(const int32_t bearing_cd)
// Tolerance is initially 10 degrees and grows at 10 degrees for each loiter circle completed.
// get current heading.
const int32_t heading_cd = plane.gps.ground_course_cd();
const int32_t heading_cd = (wrap_360(degrees(plane.ahrs.groundspeed_vector().angle())))*100;
const int32_t heading_err_cd = wrap_180_cd(bearing_cd - heading_cd);