From 7390846851dc6f79b2c67b07e3798ef38465f3e5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 4 Jun 2020 12:17:17 +1000 Subject: [PATCH] autotest: we need more than 1500 throttle for SimpleMode test we are in stabilize and flying around, needs more than half throttle to maintain height. This test was already marginal, but addition of pressure alt in SITL pushed it over the edge --- Tools/autotest/arducopter.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index bdc4332b22..ceb7e0cf97 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -1438,7 +1438,7 @@ class AutoTestCopter(AutoTest): # switch to stabilize mode self.mavproxy.send('switch 6\n') self.wait_mode('STABILIZE') - self.set_rc(3, 1500) + self.set_rc(3, 1545) # fly south 50m self.progress("# Flying south %u meters" % side)