From 38ea62c5d7e0493b3a90f6de3557199d6a4caeef Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 26 Dec 2020 20:16:42 +1100 Subject: [PATCH] autotest: send mode change messages directly rather than via MAVProxy --- Tools/autotest/common.py | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 688d194ca9..9484cafcb0 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -3881,7 +3881,15 @@ class AutoTest(ABC): '''change vehicle flightmode''' self.wait_heartbeat() self.progress("Changing mode to %s" % mode) - self.mavproxy.send('mode %s\n' % mode) + self.send_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MODE, + mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED, + self.get_mode_from_mode_mapping(mode), + 0, + 0, + 0, + 0, + 0, + ) tstart = self.get_sim_time() while not self.mode_is(mode): custom_num = self.mav.messages['HEARTBEAT'].custom_mode