From e7467ec8ca2a98422e86b25de79924fd54aafd82 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 15 Aug 2023 20:45:56 -0700 Subject: [PATCH] Tools/autotest: fix Deepstall CI Backport from PR https://github.com/ArduPilot/ardupilot/pull/24667 --- Tools/autotest/arduplane.py | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 1a08f44f3b..7687754b46 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -625,18 +625,18 @@ class AutoTestPlane(AutoTest): self.change_mode("AUTO") self.wait_ready_to_arm() self.arm_vehicle() - self.progress("Waiting for deepstall messages") - - # note that the following two don't necessarily happen in this - # order, but at very high speedups we may miss the elevator - # PWM if we first look for the text (due to the get_sim_time() - # in wait_servo_channel_value) - self.context_collect('STATUSTEXT') + self.wait_current_waypoint(4) # assume elevator is on channel 2: self.wait_servo_channel_value(2, deepstall_elevator_pwm, timeout=240) - self.wait_text("Deepstall: Entry: ", check_context=True, timeout=60) + self.progress("Waiting for stage DEEPSTALL_STAGE_LAND") + self.assert_receive_message( + 'DEEPSTALL', + condition='DEEPSTALL.stage==6', + timeout=240, + ) + self.progress("Reached stage DEEPSTALL_STAGE_LAND") self.disarm_wait(timeout=120) self.set_current_waypoint(0, check_afterwards=False)