mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
tweak to the Loiter N turns
This commit is contained in:
parent
7285cf28e2
commit
9500171a46
@ -1309,8 +1309,7 @@ static void update_nav_wp()
|
||||
if (loiter_delta < -180) loiter_delta += 360;
|
||||
|
||||
// sum the angle around the WP
|
||||
loiter_sum += abs(loiter_delta);
|
||||
|
||||
loiter_sum += loiter_delta;
|
||||
|
||||
// create a virtual waypoint that circles the next_WP
|
||||
// Count the degrees we have circulated the WP
|
||||
|
@ -454,7 +454,7 @@ static bool verify_loiter_turns()
|
||||
{
|
||||
// have we rotated around the center enough times?
|
||||
// -----------------------------------------------
|
||||
if(loiter_sum > loiter_total) {
|
||||
if(abs(loiter_sum) > loiter_total) {
|
||||
loiter_total = 0;
|
||||
loiter_sum = 0;
|
||||
//gcs_send_text_P(SEVERITY_LOW,PSTR("verify_must: LOITER orbits complete"));
|
||||
|
Loading…
Reference in New Issue
Block a user