mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
Tools: copter test parameter validation waits 10sec before starting
This allows the GPS driver to initialise which avoids an EKF3 source requires GPS failure
This commit is contained in:
parent
bb926a2976
commit
2f51b59de4
@ -5660,6 +5660,8 @@ class AutoTestCopter(AutoTest):
|
||||
self.wait_groundspeed(0, 2)
|
||||
|
||||
def test_parameter_validation(self):
|
||||
# wait 10 seconds for initialisation
|
||||
self.delay_sim_time(10)
|
||||
self.progress("invalid; min must be less than max:")
|
||||
self.set_parameter("MOT_PWM_MIN", 100)
|
||||
self.set_parameter("MOT_PWM_MAX", 50)
|
||||
|
Loading…
Reference in New Issue
Block a user