autotest: add test for mot_pwm validation
This commit is contained in:
parent
74e3ca75a7
commit
346471258b
@ -4280,6 +4280,28 @@ class AutoTestCopter(AutoTest):
|
||||
self.customise_SITL_commandline(command_line_args)
|
||||
self.fly_rangefinder_drivers_fly([x[0] for x in do_drivers])
|
||||
|
||||
def test_parameter_validation(self):
|
||||
self.progress("invalid; min must be less than max:")
|
||||
self.set_parameter("MOT_PWM_MIN", 100)
|
||||
self.set_parameter("MOT_PWM_MAX", 50)
|
||||
self.drain_mav()
|
||||
self.assert_prearm_failure("Check MOT_PWM_MIN/MAX")
|
||||
self.progress("invalid; min must be less than max (equal case):")
|
||||
self.set_parameter("MOT_PWM_MIN", 100)
|
||||
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 tests(self):
|
||||
'''return list of all tests'''
|
||||
ret = super(AutoTestCopter, self).tests()
|
||||
@ -4506,6 +4528,10 @@ class AutoTestCopter(AutoTest):
|
||||
"Fly motor vibration test",
|
||||
self.fly_motor_vibration),
|
||||
|
||||
("ParameterValidation",
|
||||
"Test parameters are checked for validity",
|
||||
self.test_parameter_validation),
|
||||
|
||||
("LogDownLoad",
|
||||
"Log download",
|
||||
lambda: self.log_download(
|
||||
|
Loading…
Reference in New Issue
Block a user