autotest: care not which CAN GPS is unhealthy when in maintenance mode

This commit is contained in:
Peter Barker 2023-06-06 20:13:31 +10:00 committed by Peter Barker
parent 533577924e
commit d0f06beeaa

View File

@ -2695,7 +2695,7 @@ class AutoTestCopter(AutoTest):
0, 0,
timeout=10, timeout=10,
want_result=mavutil.mavlink.MAV_RESULT_FAILED) want_result=mavutil.mavlink.MAV_RESULT_FAILED)
self.wait_statustext("Node {} unhealthy".format(gps1_nodeid), check_context=True) self.wait_statustext(".*Node .* unhealthy", check_context=True, regex=True)
self.stop_sup_program(instance=0) self.stop_sup_program(instance=0)
self.start_sup_program(instance=0) self.start_sup_program(instance=0)
self.stop_sup_program(instance=1) self.stop_sup_program(instance=1)