autotest: restart both CAN nodes in CAN prearm test

the node id we put into maintenane mode varies
This commit is contained in:
Peter Barker 2023-06-04 09:36:06 +10:00 committed by Peter Barker
parent a710a75b6b
commit 35ebc25172
1 changed files with 4 additions and 0 deletions

View File

@ -2681,6 +2681,8 @@ class AutoTestCopter(AutoTest):
self.set_parameter("ARMING_CHECK", 1)
self.stop_sup_program(instance=0)
self.start_sup_program(instance=0, args="-M")
self.stop_sup_program(instance=1)
self.start_sup_program(instance=1, args="-M")
self.delay_sim_time(2)
self.context_collect('STATUSTEXT')
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
@ -2696,6 +2698,8 @@ class AutoTestCopter(AutoTest):
self.wait_statustext("Node {} unhealthy".format(gps1_nodeid), check_context=True)
self.stop_sup_program(instance=0)
self.start_sup_program(instance=0)
self.stop_sup_program(instance=1)
self.start_sup_program(instance=1)
self.context_stop_collecting('STATUSTEXT')
self.context_pop()
self.CopterMission()