diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index e4acbb1b7d..289b1b6b43 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -5229,7 +5229,7 @@ class AutoTestHeli(AutoTestCopter): self.arm_vehicle() self.set_rc(8, 2000) self.progress("wait for rotor runup to complete") - self.wait_servo_channel_value(8, 1900, timeout=10) + self.wait_servo_channel_value(8, 1660, timeout=10) self.delay_sim_time(20) # check we are still on the ground... m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) @@ -5345,7 +5345,7 @@ class AutoTestHeli(AutoTestCopter): self.arm_vehicle() self.set_rc(8, 2000) self.progress("wait for rotor runup to complete") - self.wait_servo_channel_value(8, 1900, timeout=10) + self.wait_servo_channel_value(8, 1660, timeout=10) self.delay_sim_time(20) self.set_rc(3, 2000) self.wait_altitude(start_alt - 1,