mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Tweak to make circle mode scripting more accurate
This commit is contained in:
parent
89343ae306
commit
72faa6525e
@ -290,7 +290,7 @@ static void do_loiter_turns()
|
||||
wp_control = CIRCLE_MODE;
|
||||
|
||||
// reset desired location
|
||||
circle_angle = 0;
|
||||
|
||||
|
||||
if(command_nav_queue.lat == 0){
|
||||
// allow user to specify just the altitude
|
||||
@ -305,6 +305,10 @@ static void do_loiter_turns()
|
||||
loiter_total = command_nav_queue.p1 * 360;
|
||||
loiter_sum = 0;
|
||||
old_target_bearing = target_bearing;
|
||||
|
||||
circle_angle = target_bearing + 18000;
|
||||
circle_angle = wrap_360(circle_angle);
|
||||
circle_angle *= RADX100;
|
||||
}
|
||||
|
||||
static void do_loiter_time()
|
||||
|
Loading…
Reference in New Issue
Block a user