Browse Source

Plane: Use AHRS for heading in mode loiter

zr-v5.1
Rishabh 5 years ago committed by Andrew Tridgell
parent
commit
6989cb0131
  1. 2
      ArduPlane/mode_loiter.cpp

2
ArduPlane/mode_loiter.cpp

@ -52,7 +52,7 @@ bool ModeLoiter::isHeadingLinedUp_cd(const int32_t bearing_cd) @@ -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);

Loading…
Cancel
Save