AP_L1_Control: update_waypoint wrap added to nav_bearing

Co-authored-by: Iampete1 <iampete@hotmail.co.uk>
This commit is contained in:
xianglunkai 2022-02-15 20:34:28 +09:00 committed by Andrew Tridgell
parent 4f785b4aaa
commit beb194b4a1
1 changed files with 1 additions and 1 deletions

View File

@ -313,7 +313,7 @@ void AP_L1_Control::update_waypoint(const struct Location &prev_WP, const struct
Nu1 += _L1_xtrack_i;
Nu = Nu1 + Nu2;
_nav_bearing = atan2f(AB.y, AB.x) + Nu1; // bearing (radians) from AC to L1 point
_nav_bearing = wrap_PI(atan2f(AB.y, AB.x) + Nu1); // bearing (radians) from AC to L1 point
}
_prevent_indecision(Nu);