From cbe1dba781b14b0c482aed1149bda451f4b83db2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 2 Apr 2020 08:22:14 +1100 Subject: [PATCH] autotest: loosen slowdown constraint on zigzag test --- Tools/autotest/arducopter.py | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 94db98e321..95b8b6cfd0 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -2588,6 +2588,7 @@ class AutoTestCopter(AutoTest): ZIGZAG = 24 j = 0 + slowdown_speed = 0.3 # because Copter takes a long time to actually stop self.start_subtest("Conduct ZigZag test for all 4 directions") while j < 4: self.progress("## Align heading with the run-way (j=%d)##" % j) @@ -2601,7 +2602,7 @@ class AutoTestCopter(AutoTest): self.set_rc(1, 1700) # fly side-way for 20m self.wait_distance(20) self.set_rc(1, 1500) - self.wait_groundspeed(0, 0.20) # wait until the copter slows down + self.wait_groundspeed(0, slowdown_speed) # wait until the copter slows down self.progress("## Record Point A ##") self.set_rc(8, 1500) # pilot always have to cross mid position when changing for low to high position self.set_rc(8, 1900) # record point B @@ -2613,23 +2614,23 @@ class AutoTestCopter(AutoTest): self.set_rc(2, 1300) self.wait_distance(10) self.set_rc(2, 1500) # re-centre pitch rc control - self.wait_groundspeed(0, 0.2) # wait until the copter slows down + self.wait_groundspeed(0, slowdown_speed) # wait until the copter slows down self.set_rc(8, 1500) # switch to mid position self.progress("## auto execute vector BA ##") self.set_rc(8, 1100) self.wait_distance(17) # wait for it to finish - self.wait_groundspeed(0, 0.2) # wait until the copter slows down + self.wait_groundspeed(0, slowdown_speed) # wait until the copter slows down self.progress("## fly forward for 10 meter ##") self.set_rc(2, 1300) # fly forward for 10 meter self.wait_distance(10) self.set_rc(2, 1500) # re-centre pitch rc control - self.wait_groundspeed(0, 0.2) # wait until the copter slows down + self.wait_groundspeed(0, slowdown_speed) # wait until the copter slows down self.set_rc(8, 1500) # switch to mid position self.progress("## auto execute vector AB ##") self.set_rc(8, 1900) self.wait_distance(17) # wait for it to finish - self.wait_groundspeed(0, 0.2) # wait until the copter slows down + self.wait_groundspeed(0, slowdown_speed) # wait until the copter slows down i=i+1 # test the case when pilot switch to manual control during the auto flight self.start_subtest("test the case when pilot switch to manual control during the auto flight") @@ -2643,21 +2644,21 @@ class AutoTestCopter(AutoTest): self.set_rc(8, 1100) # switch to low position, auto execute vector BA self.wait_distance(8) # purposely switch to manual halfway self.set_rc(8, 1500) - self.wait_groundspeed(0, 0.2) # copter should slow down here + self.wait_groundspeed(0, slowdown_speed) # copter should slow down here self.progress("## Manual control to fly forward ##") self.set_rc(2, 1300) # manual control to fly forward self.wait_distance(8) self.set_rc(2, 1500) # re-centre pitch rc control - self.wait_groundspeed(0, 0.2) # wait until the copter slows down + self.wait_groundspeed(0, slowdown_speed) # wait until the copter slows down self.progress("## continue vector BA ##") self.set_rc(8, 1100) # copter should continue mission here self.wait_distance(8) # wait for it to finish rest of BA - self.wait_groundspeed(0, 0.2) #wait until the copter slows down + self.wait_groundspeed(0, slowdown_speed) #wait until the copter slows down self.set_rc(8, 1500) # switch to mid position self.progress("## auto execute vector AB ##") self.set_rc(8, 1900) # switch to execute AB again self.wait_distance(17) # wait for it to finish - self.wait_groundspeed(0, 0.2) # wait until the copter slows down + self.wait_groundspeed(0, slowdown_speed) # wait until the copter slows down self.change_mode('LOITER') j=j+1