mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
autotest: move assert_mission_count up, use it
This commit is contained in:
parent
30c9d4bcf4
commit
f7d8994ce1
@ -5694,15 +5694,6 @@ class AutoTestCopter(AutoTest):
|
|||||||
if ex is not None:
|
if ex is not None:
|
||||||
raise ex
|
raise ex
|
||||||
|
|
||||||
def get_mission_count(self):
|
|
||||||
return self.get_parameter("MIS_TOTAL")
|
|
||||||
|
|
||||||
def assert_mission_count(self, expected):
|
|
||||||
count = self.get_mission_count()
|
|
||||||
if count != expected:
|
|
||||||
raise NotAchievedException("Unexpected count got=%u want=%u" %
|
|
||||||
(count, expected))
|
|
||||||
|
|
||||||
def test_aux_switch_options(self):
|
def test_aux_switch_options(self):
|
||||||
self.set_parameter("RC7_OPTION", 58) # clear waypoints
|
self.set_parameter("RC7_OPTION", 58) # clear waypoints
|
||||||
self.load_mission("copter_loiter_to_alt.txt")
|
self.load_mission("copter_loiter_to_alt.txt")
|
||||||
|
@ -2691,6 +2691,15 @@ class AutoTest(ABC):
|
|||||||
self.set_rc(ch, 1000)
|
self.set_rc(ch, 1000)
|
||||||
self.delay_sim_time(1)
|
self.delay_sim_time(1)
|
||||||
|
|
||||||
|
def get_mission_count(self):
|
||||||
|
return self.get_parameter("MIS_TOTAL")
|
||||||
|
|
||||||
|
def assert_mission_count(self, expected):
|
||||||
|
count = self.get_mission_count()
|
||||||
|
if count != expected:
|
||||||
|
raise NotAchievedException("Unexpected count got=%u want=%u" %
|
||||||
|
(count, expected))
|
||||||
|
|
||||||
def clear_wp(self, ch=8):
|
def clear_wp(self, ch=8):
|
||||||
"""Trigger RC Aux to clear waypoint."""
|
"""Trigger RC Aux to clear waypoint."""
|
||||||
self.progress("Clearing waypoints")
|
self.progress("Clearing waypoints")
|
||||||
@ -2699,8 +2708,7 @@ class AutoTest(ABC):
|
|||||||
self.set_rc(ch, 2000)
|
self.set_rc(ch, 2000)
|
||||||
self.delay_sim_time(0.5)
|
self.delay_sim_time(0.5)
|
||||||
self.set_rc(ch, 1000)
|
self.set_rc(ch, 1000)
|
||||||
self.mavproxy.send('wp list\n')
|
self.assert_mission_count(0)
|
||||||
self.mavproxy.expect('Requesting 0 waypoints')
|
|
||||||
|
|
||||||
def log_list(self):
|
def log_list(self):
|
||||||
'''return a list of log files present in POSIX-style loging dir'''
|
'''return a list of log files present in POSIX-style loging dir'''
|
||||||
|
Loading…
Reference in New Issue
Block a user