forked from Archive/PX4-Autopilot
Merge pull request #666 from PX4/fix_loiter
Navigator: set loiter WP correctly
This commit is contained in:
commit
51b7c27363
|
@ -1080,9 +1080,8 @@ Navigator::start_loiter()
|
|||
mavlink_log_info(_mavlink_fd, "[navigator] loiter at current altitude");
|
||||
}
|
||||
|
||||
_pos_sp_triplet.current.type = SETPOINT_TYPE_LOITER;
|
||||
}
|
||||
|
||||
_pos_sp_triplet.current.type = SETPOINT_TYPE_LOITER;
|
||||
_pos_sp_triplet.current.loiter_radius = _parameters.loiter_radius;
|
||||
_pos_sp_triplet.current.loiter_direction = 1;
|
||||
_pos_sp_triplet.previous.valid = false;
|
||||
|
|
Loading…
Reference in New Issue