Tools: autotest: clear Rover waypoints before toggling them in

This commit is contained in:
Peter Barker 2018-09-06 14:32:00 +10:00 committed by Peter Barker
parent bb99165221
commit 5d317a8ef7
2 changed files with 6 additions and 3 deletions

View File

@ -146,6 +146,8 @@ class AutoTestRover(AutoTest):
self.set_parameter("RC7_OPTION", 7)
self.set_parameter("RC8_OPTION", 58)
self.clear_wp()
# use LEARNING Mode
self.mavproxy.send('switch 5\n')
self.wait_mode('MANUAL')
@ -198,10 +200,8 @@ class AutoTestRover(AutoTest):
raise NotAchievedException()
# TODO: actually drive the mission
self.progress("Clearing waypoints")
self.clear_wp()
self.mavproxy.send('wp list\n')
self.mavproxy.expect('Requesting 0 waypoints')
except Exception as e:
self.progress("Caught exception: %s" % str(e))
ex = e

View File

@ -332,11 +332,14 @@ class AutoTest(ABC):
def clear_wp(self):
"""Trigger RC 8 to clear waypoint."""
self.progress("Clearing waypoints")
self.set_rc(8, 1000)
self.wait_seconds(0.5)
self.set_rc(8, 2000)
self.wait_seconds(0.5)
self.set_rc(8, 1000)
self.mavproxy.send('wp list\n')
self.mavproxy.expect('Requesting 0 waypoints')
def log_download(self, filename, timeout=360):
"""Download latest log."""