Tools: copter : make zigzag more verbose

This commit is contained in:
Pierre Kancir 2020-02-27 10:21:18 +01:00 committed by Peter Barker
parent f24f97e51b
commit 3f441e61cd
1 changed files with 27 additions and 12 deletions

View File

@ -2587,59 +2587,74 @@ class AutoTestCopter(AutoTest):
self.takeoff(alt_min=5, mode='LOITER')
ZIGZAG = 24
j=0
while j<4: # conduct test for all 4 directions
j = 0
self.start_subtest("Conduct ZigZag test for all 4 directions")
while j < 4:
self.progress("## Align heading with the run-way (j=%d)##" % j)
self.set_rc(8, 1500)
self.set_rc(4, 1420)
self.wait_heading(352-j*90) # align heading with the run-way
self.wait_heading(352-j*90)
self.set_rc(4, 1500)
self.change_mode(ZIGZAG)
self.progress("## Record Point A ##")
self.set_rc(8, 1100) # record point A
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.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
i=1
while i<2: # run zigzag A->B and B->A for 5 times
self.set_rc(2, 1300) # fly forward for 10 meter
while i < 2:
self.start_subtest("Run zigzag A->B and B->A (i=%d)" % i)
self.progress("## fly forward for 10 meter ##")
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, 0.2) # wait until the copter slows down
self.set_rc(8, 1500) # switch to mid position
self.set_rc(8, 1100) # auto execute vector BA
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, 0.2) # 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, 0.2) # wait until the copter slows down
self.set_rc(8, 1500) # switch to mid position
self.set_rc(8, 1900) # auto execute vector AB
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, 0.2) # 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")
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, 0.2) # 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) # 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.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.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.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