From a47a306a83ce97670374c48557f2799455185ba0 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 4 Sep 2021 19:38:03 +0100 Subject: [PATCH] Tools: autotest: copter: remove check for PWM min/max zero --- Tools/autotest/arducopter.py | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index eb90b2ae44..b88d583f0a 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -6502,16 +6502,6 @@ class AutoTestCopter(AutoTest): self.set_parameter("MOT_PWM_MAX", 100) self.drain_mav() self.assert_prearm_failure("Check MOT_PWM_MIN/MAX") - self.progress("invalid; both must be non-zero or both zero (min=0)") - self.set_parameter("MOT_PWM_MIN", 0) - self.set_parameter("MOT_PWM_MAX", 100) - self.drain_mav() - self.assert_prearm_failure("Check MOT_PWM_MIN/MAX") - self.progress("invalid; both must be non-zero or both zero (max=0)") - self.set_parameter("MOT_PWM_MIN", 100) - self.set_parameter("MOT_PWM_MAX", 0) - self.drain_mav() - self.assert_prearm_failure("Check MOT_PWM_MIN/MAX") def test_alt_estimate_prearm(self): self.context_push()