From c63d12b6c9c131f7873460fdeab713e5882f238d Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Thu, 12 Aug 2021 14:17:25 -0300 Subject: [PATCH] Autotest: Sub: fix sub tests for new althold implementation With this implementation (same as copter's) 1450 is within the pilot deadzone, which breaks the test. --- Tools/autotest/ardusub.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index 9183ab8be0..b9a94fd41b 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -162,7 +162,7 @@ class AutoTestSub(AutoTest): # Make sure that the ROV will dive with a small input down even if there is a 10N buoyancy force upwards self.set_parameter("SIM_BUOYANCY", 10) - self.set_rc(Joystick.Throttle, 1450) + self.set_rc(Joystick.Throttle, 1350) self.wait_altitude(altitude_min=-6, altitude_max=-5.5) self.set_rc(Joystick.Throttle, 1500)