mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Looking for larger than 255 numbers
This commit is contained in:
parent
3cf77729ef
commit
fa2d84e557
@ -206,7 +206,7 @@ def wait_waypoint(mav, wpnum_start, wpnum_end, allow_skip=True, max_dist=2, time
|
||||
if (current_wp == wpnum_end and wp_dist < max_dist):
|
||||
print("Reached final waypoint %u" % seq)
|
||||
return True
|
||||
if (current_wp == 255):
|
||||
if (seq >= 255):
|
||||
print("Reached final waypoint %u" % seq)
|
||||
return True
|
||||
if seq > current_wp+1:
|
||||
|
Loading…
Reference in New Issue
Block a user