From fa37ad344b34ac88ec621a831f4df75cd4b5b8ec Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 3 Feb 2019 21:43:07 +1100 Subject: [PATCH] Tools: autotest: refactor setting of rc defaults --- Tools/autotest/apmrover2.py | 9 +++++---- Tools/autotest/arducopter.py | 17 +++++++++-------- Tools/autotest/arduplane.py | 9 +++++---- Tools/autotest/balancebot.py | 7 ++++--- Tools/autotest/common.py | 30 ++++++++++++++++++++++++++++-- 5 files changed, 51 insertions(+), 21 deletions(-) diff --git a/Tools/autotest/apmrover2.py b/Tools/autotest/apmrover2.py index 90b704f3d4..a742bf739e 100644 --- a/Tools/autotest/apmrover2.py +++ b/Tools/autotest/apmrover2.py @@ -1014,10 +1014,11 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) ]) return ret - def set_rc_default(self): - super(AutoTestRover, self).set_rc_default() - self.set_rc(3, 1000) - self.set_rc(8, 1800) + def rc_defaults(self): + ret = super(AutoTestRover, self).rc_defaults() + ret[3] = 1000 + ret[8] = 1800 + return ret; def default_mode(self): return 'MANUAL' diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index d1cc733c51..84bb7b9dfc 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -2574,9 +2574,10 @@ class AutoTestCopter(AutoTest): def default_mode(self): return "STABILIZE" - def set_rc_default(self): - super(AutoTestCopter, self).set_rc_default() - self.set_rc(3, 1000) + def rc_defaults(self): + ret = super(AutoTestCopter, self).rc_defaults() + ret[3] = 1000 + return ret def tests(self): '''return list of all tests''' @@ -2742,11 +2743,11 @@ class AutoTestHeli(AutoTestCopter): AVCHOME.heading) self.frame = 'heli' - def set_rc_default(self): - super(AutoTestCopter, self).set_rc_default() - self.progress("Lowering rotor speed") - self.set_rc(8, 1000) - self.set_rc(3, 1000) # collective + def rc_defaults(self): + ret = super(AutoTestHeli, self).rc_defaults() + ret[8] = 1000 + ret[3] = 1000 # collective + return ret def tests(self): '''return list of all tests''' diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index e84f474bd1..7ca369797b 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -730,10 +730,11 @@ class AutoTestPlane(AutoTest): lambda: self.fly_mission( os.path.join(testdir, "ap1.txt"))) - def set_rc_default(self): - super(AutoTestPlane, self).set_rc_default() - self.set_rc(3, 1000) - self.set_rc(8, 1800) + def rc_defaults(self): + ret = super(AutoTestPlane, self).rc_defaults() + ret[3] = 1000 + ret[8] = 1800 + return ret def default_mode(self): return "MANUAL" diff --git a/Tools/autotest/balancebot.py b/Tools/autotest/balancebot.py index 17333e1728..129a042bed 100644 --- a/Tools/autotest/balancebot.py +++ b/Tools/autotest/balancebot.py @@ -53,9 +53,10 @@ class AutoTestBalanceBot(AutoTestRover): self.do_set_mode_via_command_long("HOLD") self.do_set_mode_via_command_long("MANUAL") - def set_rc_default(self): - super(AutoTestBalanceBot, self).set_rc_default() - self.set_rc(3, 1500) + def rc_defaults(self): + ret = super(AutoTestBalanceBot, self).rc_defaults() + ret[3] = 1500 + return ret def tests(self): '''return list of all tests''' diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index ff4e8a29de..9d607deb4b 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -602,10 +602,36 @@ class AutoTest(ABC): self.progress("num_wp: %d" % num_wp) return num_wp + def rc_defaults(self): + return { + 1: 1500, + 2: 1500, + 3: 1500, + 4: 1500, + 5: 1500, + 6: 1500, + 7: 1500, + 8: 1500, + 9: 1500, + 10: 1500, + 11: 1500, + 12: 1500, + 13: 1500, + 14: 1500, + 15: 1500, + 16: 1500, + } + + def set_rc_from_map(self, _map): + for chan in _map: + value = _map[chan] + self.set_rc(chan, value) +# self.mavproxy.send('rc %u value\n' % (chan, value)) + def set_rc_default(self): """Setup all simulated RC control to 1500.""" - for chan in range(1, 16): - self.mavproxy.send('rc %u 1500\n' % chan) + _defaults = self.rc_defaults() + self.set_rc_from_map(_defaults) def set_rc(self, chan, pwm, timeout=2000): """Setup a simulated RC control to a PWM value"""