Tools: autotest: copter: remove check for PWM min/max zero

This commit is contained in:
Iampete1 2021-09-04 19:38:03 +01:00 committed by Willian Galvani
parent 1e5d500e26
commit a47a306a83
1 changed files with 0 additions and 10 deletions

View File

@ -6502,16 +6502,6 @@ class AutoTestCopter(AutoTest):
self.set_parameter("MOT_PWM_MAX", 100) self.set_parameter("MOT_PWM_MAX", 100)
self.drain_mav() self.drain_mav()
self.assert_prearm_failure("Check MOT_PWM_MIN/MAX") 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): def test_alt_estimate_prearm(self):
self.context_push() self.context_push()