navigator hotfix: Increase acceptance range for yaw setpoints.

This commit is contained in:
Lorenz Meier 2014-04-05 16:45:23 +02:00
parent 0f03216232
commit 7b95d36405
1 changed files with 1 additions and 1 deletions

View File

@ -1539,7 +1539,7 @@ Navigator::check_mission_item_reached()
/* check yaw if defined only for rotary wing except takeoff */
float yaw_err = _wrap_pi(_mission_item.yaw - _global_pos.yaw);
if (fabsf(yaw_err) < 0.05f) { /* XXX get rid of magic number */
if (fabsf(yaw_err) < 0.2f) { /* XXX get rid of magic number */
_waypoint_yaw_reached = true;
}