From 7034ef2df701067c4b7b82986febd870f2e545fd Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 9 Apr 2019 15:35:19 +1000 Subject: [PATCH] Tools: autotest: raise throttle in loiter mode This avoids the vehicle hitting the ground while we're looking for messages. --- Tools/autotest/arducopter.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index f367f1845d..57f4cab566 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -2230,6 +2230,7 @@ class AutoTestCopter(AutoTest): def test_position_target_message_mode(self): " Ensure that POSITION_TARGET_LOCAL_NED messages are sent in Guided Mode only " + self.hover() self.change_mode('LOITER') self.progress("Setting POSITION_TARGET_LOCAL_NED message rate to 10Hz") self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, 10)