From 35ebc2517213ba3d925eaec1e438b2f16c39b48f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 4 Jun 2023 09:36:06 +1000 Subject: [PATCH] autotest: restart both CAN nodes in CAN prearm test the node id we put into maintenane mode varies --- Tools/autotest/arducopter.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 592ef0a31a..c2547b2dfc 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -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()