autotest: add test for changing modes by mode number

Useful for when you don't have a mapping entry for the mode number yet
This commit is contained in:
Peter Barker 2022-07-10 20:56:45 +10:00 committed by Peter Barker
parent a92161cd18
commit a672c7df97

View File

@ -5931,6 +5931,17 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.assert_prearm_failure("Motors Emergency Stopped") self.assert_prearm_failure("Motors Emergency Stopped")
self.context_pop() self.context_pop()
def assert_mode(self, mode):
if not self.mode_is(mode):
raise NotAchievedException("Mode is not %s" % str(mode))
def ChangeModeByNumber(self):
'''ensure we can set a mode by number, handy when we don't have a
pymavlink number for it yet'''
for (x, want) in (0, 'MANUAL'), (1, 'ACRO'), (3, 3):
self.change_mode(x)
self.assert_mode(want)
def tests(self): def tests(self):
'''return list of all tests''' '''return list of all tests'''
ret = super(AutoTestRover, self).tests() ret = super(AutoTestRover, self).tests()
@ -6173,6 +6184,10 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
"Test mulitple depthfinders for boats", "Test mulitple depthfinders for boats",
self.test_depthfinder), self.test_depthfinder),
("ChangeModeByNumber",
"Test changing mode by number",
self.ChangeModeByNumber),
("EStopAtBoot", ("EStopAtBoot",
"Ensure EStop prevents arming when asserted at boot time", "Ensure EStop prevents arming when asserted at boot time",
self.EStopAtBoot), self.EStopAtBoot),