Tools: autotest: correct debounce tests under Rover

Channel 8 is the mode channel under Rover
This commit is contained in:
SergeyBokhantsev 2019-06-18 18:37:19 +03:00 committed by Peter Barker
parent bf6f10e448
commit c9447776b2
2 changed files with 13 additions and 13 deletions

View File

@ -59,7 +59,7 @@ class AutoTestRover(AutoTest):
try:
self.progress("TEST SQUARE")
self.set_parameter("RC7_OPTION", 7)
self.set_parameter("RC8_OPTION", 58)
self.set_parameter("RC9_OPTION", 58)
self.mavproxy.send('switch 5\n')
self.wait_mode('MANUAL')
@ -67,7 +67,7 @@ class AutoTestRover(AutoTest):
self.wait_ready_to_arm()
self.arm_vehicle()
self.clear_wp()
self.clear_wp(9)
# first aim north
self.progress("\nTurn right towards north")
@ -120,7 +120,7 @@ class AutoTestRover(AutoTest):
# TODO: actually drive the mission
self.clear_wp()
self.clear_wp(9)
except Exception as e:
self.progress("Caught exception: %s" % str(e))
ex = e

View File

@ -507,23 +507,23 @@ class AutoTest(ABC):
0,
math.degrees(m.yaw))
def save_wp(self):
"""Trigger RC 7 to save waypoint."""
self.set_rc(7, 1000)
def save_wp(self, ch=7):
"""Trigger RC Aux to save waypoint."""
self.set_rc(ch, 1000)
self.wait_seconds(1)
self.set_rc(7, 2000)
self.set_rc(ch, 2000)
self.wait_seconds(1)
self.set_rc(7, 1000)
self.set_rc(ch, 1000)
self.wait_seconds(1)
def clear_wp(self):
"""Trigger RC 8 to clear waypoint."""
def clear_wp(self, ch=8):
"""Trigger RC Aux to clear waypoint."""
self.progress("Clearing waypoints")
self.set_rc(8, 1000)
self.set_rc(ch, 1000)
self.wait_seconds(0.5)
self.set_rc(8, 2000)
self.set_rc(ch, 2000)
self.wait_seconds(0.5)
self.set_rc(8, 1000)
self.set_rc(ch, 1000)
self.mavproxy.send('wp list\n')
self.mavproxy.expect('Requesting 0 waypoints')