From 9e46c02999e2aaaa7526619e6e62fc787fb39ba1 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 17 Nov 2024 15:07:06 +0000 Subject: [PATCH] Tools: autotest: quadplane: MAV_CMD_DO_ENGINE_CONTROL: wait after RC input change before sending command --- Tools/autotest/quadplane.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 0e6ef03d3f6c2..3a6aff9163843 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -1220,6 +1220,7 @@ def MAV_CMD_DO_ENGINE_CONTROL(self): self.start_subtest("Check start chan control disable") old_start_channel_value = self.get_rc_channel_value(rc_engine_start_chan) self.set_rc(rc_engine_start_chan, 1000) + self.delay_sim_time(1) # Make sure the RC change has registered self.context_collect('STATUSTEXT') method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=1, want_result=mavutil.mavlink.MAV_RESULT_FAILED) self.wait_statustext("start control disabled", check_context=True)