Tools: autotest: quadplane: MAV_CMD_DO_ENGINE_CONTROL: wait after RC input change before sending command

This commit is contained in:
Iampete1 2024-11-17 15:07:06 +00:00 committed by Andrew Tridgell
parent 9185430797
commit 6400ce5833

View File

@ -1233,6 +1233,7 @@ class AutoTestQuadPlane(vehicle_test_suite.TestSuite):
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)