mirror of https://github.com/ArduPilot/ardupilot
autotest: FETtec tests: give vehicle a chance to realise ESCs are dead
Should remove the race condition where we disable an ESC but the vehicle doesn't realise and lets the vehicle arm. Also, waiting this long causes the ESCs to just go missing, not give a telemetry failure
This commit is contained in:
parent
59bda177ff
commit
d0872abdf9
|
@ -7387,21 +7387,24 @@ class AutoTestCopter(AutoTest):
|
|||
for mot_id_to_kill in 1, 2:
|
||||
self.progress("Turning ESC=%u off" % mot_id_to_kill)
|
||||
self.set_parameter("SIM_FTOWESC_POW", mask & ~(1 << mot_id_to_kill))
|
||||
self.assert_prearm_failure("are not sending tel")
|
||||
self.delay_sim_time(1)
|
||||
self.assert_prearm_failure("are not running")
|
||||
self.progress("Turning it back on")
|
||||
self.set_parameter("SIM_FTOWESC_POW", mask)
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
self.progress("Turning ESC=%u off (again)" % mot_id_to_kill)
|
||||
self.set_parameter("SIM_FTOWESC_POW", mask & ~(1 << mot_id_to_kill))
|
||||
self.assert_prearm_failure("are not sending tel")
|
||||
self.delay_sim_time(1)
|
||||
self.assert_prearm_failure("are not running")
|
||||
self.progress("Turning it back on")
|
||||
self.set_parameter("SIM_FTOWESC_POW", mask)
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
self.progress("Turning all ESCs off")
|
||||
self.set_parameter("SIM_FTOWESC_POW", 0)
|
||||
self.assert_prearm_failure("are not sending tel")
|
||||
self.delay_sim_time(1)
|
||||
self.assert_prearm_failure("are not running")
|
||||
self.progress("Turning them back on")
|
||||
self.set_parameter("SIM_FTOWESC_POW", mask)
|
||||
self.wait_ready_to_arm()
|
||||
|
|
Loading…
Reference in New Issue