From a8ca41abf1a69bf4115a8d29dd9be7146fbf7e5d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 4 Apr 2016 11:28:28 +1000 Subject: [PATCH] autotest: use 60% engine speed for stability test can't handle 55% in SITL now in quad --- Tools/autotest/arducopter.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index d2874fe37b..650ded3a4b 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -362,8 +362,8 @@ def fly_stability_patch(mavproxy, mav, holdtime=30, maxaltchange=5, maxdistchang print("Holding loiter at %u meters for %u seconds" % (start_altitude, holdtime)) # cut motor 1 to 55% efficiency - print("Cutting motor 1 to 55% efficiency") - mavproxy.send('param set SIM_ENGINE_MUL 0.55\n') + print("Cutting motor 1 to 60% efficiency") + mavproxy.send('param set SIM_ENGINE_MUL 0.60\n') while get_sim_time(mav) < tstart + holdtime: m = mav.recv_match(type='VFR_HUD', blocking=True)