mirror of https://github.com/ArduPilot/ardupilot
AP_L1_Control: update_waypoint wrap added to nav_bearing
Co-authored-by: Iampete1 <iampete@hotmail.co.uk>
This commit is contained in:
parent
4f785b4aaa
commit
beb194b4a1
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue