Tools: rover: correct test_setting_modes_via_mavproxy_switch for RTL and AUTO

This commit is contained in:
Pierre Kancir 2020-12-13 23:57:20 +01:00 committed by Randy Mackay
parent 871b9fc12d
commit 7a2a60e65c
2 changed files with 8 additions and 2 deletions

View File

@ -0,0 +1,4 @@
QGC WPL 110
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 -0.110000 1
1 0 0 20 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
2 0 3 17 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1

View File

@ -571,11 +571,13 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.progress("Pin mask changed after relay command") self.progress("Pin mask changed after relay command")
def test_setting_modes_via_mavproxy_switch(self): def test_setting_modes_via_mavproxy_switch(self):
self.load_mission(self.arming_test_mission())
self.wait_ready_to_arm()
fnoo = [(1, 'MANUAL'), fnoo = [(1, 'MANUAL'),
(2, 'MANUAL'), (2, 'MANUAL'),
(3, 'RTL'), (3, 'RTL'),
# (4, 'AUTO'), # no mission, can't set auto (4, 'AUTO'),
(5, 'RTL'), # non-existant mode, should stay in RTL (5, 'AUTO'), # non-existant mode, should stay in RTL
(6, 'MANUAL')] (6, 'MANUAL')]
for (num, expected) in fnoo: for (num, expected) in fnoo:
self.mavproxy.send('switch %u\n' % num) self.mavproxy.send('switch %u\n' % num)