mirror of https://github.com/ArduPilot/ardupilot
autotest: correct Rover DriveMission test
4 would seem to have been just a magic number and could be missed on faster speedups
This commit is contained in:
parent
81740893ee
commit
cd207164a2
|
@ -6543,7 +6543,7 @@ class AutoTest(ABC):
|
|||
(seq, wp_dist, m.alt, current_wp, wpnum_end))
|
||||
last_wp_msg = self.get_sim_time_cached()
|
||||
if seq == current_wp+1 or (seq > current_wp+1 and allow_skip):
|
||||
self.progress("test: Starting new waypoint %u" % seq)
|
||||
self.progress("WW: Starting new waypoint %u" % seq)
|
||||
tstart = self.get_sim_time()
|
||||
current_wp = seq
|
||||
# the wp_dist check is a hack until we can sort out
|
||||
|
|
|
@ -395,11 +395,11 @@ class AutoTestRover(AutoTest):
|
|||
def drive_mission(self, filename, strict=True):
|
||||
"""Drive a mission from a file."""
|
||||
self.progress("Driving mission %s" % filename)
|
||||
self.load_mission(filename, strict=strict)
|
||||
wp_count = self.load_mission(filename, strict=strict)
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
self.change_mode('AUTO')
|
||||
self.wait_waypoint(1, 4, max_dist=5)
|
||||
self.wait_waypoint(1, wp_count-1, max_dist=5)
|
||||
self.wait_statustext("Mission Complete", timeout=600)
|
||||
self.disarm_vehicle()
|
||||
self.progress("Mission OK")
|
||||
|
|
Loading…
Reference in New Issue