forked from Archive/PX4-Autopilot
Merge pull request #806 from PX4/yaw_sp_fix
navigator hotfix: Increase acceptance range for yaw setpoints.
This commit is contained in:
commit
3e5f0813a8
|
@ -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;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue