Tools: autotest: update copter param validation check

This commit is contained in:
Iampete1 2022-09-15 20:46:26 +01:00 committed by Randy Mackay
parent 7cafcf7b90
commit ef9f5a9552

View File

@ -7449,14 +7449,29 @@ class AutoTestCopter(AutoTest):
"MOT_PWM_MAX": 50,
})
self.drain_mav()
self.assert_prearm_failure("Check MOT_PWM_MIN/MAX")
self.assert_prearm_failure("Motors: Check MOT_PWM_MIN and MOT_PWM_MAX")
self.progress("invalid; min must be less than max (equal case):")
self.set_parameters({
"MOT_PWM_MIN": 100,
"MOT_PWM_MAX": 100,
})
self.drain_mav()
self.assert_prearm_failure("Check MOT_PWM_MIN/MAX")
self.assert_prearm_failure("Motors: Check MOT_PWM_MIN and MOT_PWM_MAX")
self.progress("Spin min more than 0.3")
self.set_parameters({
"MOT_PWM_MIN": 1000,
"MOT_PWM_MAX": 2000,
"MOT_SPIN_MIN": 0.5,
})
self.drain_mav()
self.assert_prearm_failure("PreArm: Motors: MOT_SPIN_MIN too high 0.50 > 0.3")
self.progress("Spin arm more than spin min")
self.set_parameters({
"MOT_SPIN_MIN": 0.1,
"MOT_SPIN_ARM": 0.2,
})
self.drain_mav()
self.assert_prearm_failure("PreArm: Motors: MOT_SPIN_ARM > MOT_SPIN_MIN")
def SensorErrorFlags(self):
'''Test we get ERR messages when sensors have issues'''