diff --git a/ArduPlane/mode_loiter.cpp b/ArduPlane/mode_loiter.cpp index 344e7b0d64..3501d7553c 100644 --- a/ArduPlane/mode_loiter.cpp +++ b/ArduPlane/mode_loiter.cpp @@ -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);