mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Tools: autotest: add and update zigzag flight mode test for copter
Tools: autotest: add copter zigzag mode Tools: autotest: update copter zigzag flight test
This commit is contained in:
parent
b7d0e4ec10
commit
07747c5c09
@ -1954,6 +1954,77 @@ class AutoTestCopter(AutoTest):
|
||||
if not took_off:
|
||||
raise NotAchievedException("Did not take off")
|
||||
|
||||
def fly_zigzag_mode(self):
|
||||
'''test zigzag mode'''
|
||||
|
||||
# set channel 8 for zigzag savewp and recentre it
|
||||
self.set_parameter("RC8_OPTION", 61)
|
||||
|
||||
self.takeoff(alt_min=5, mode='LOITER')
|
||||
|
||||
ZIGZAG = 24
|
||||
j=0
|
||||
while j<4: # conduct test for all 4 directions
|
||||
self.set_rc(8, 1500)
|
||||
self.set_rc(4, 1420)
|
||||
self.wait_heading(352-j*90) # align heading with the run-way
|
||||
self.set_rc(4, 1500)
|
||||
self.change_mode(ZIGZAG)
|
||||
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.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
|
||||
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.set_rc(8, 1500) # switch to mid position
|
||||
self.set_rc(8, 1100) # auto execute vector BA
|
||||
self.wait_distance(17) # wait for it to finish
|
||||
self.wait_groundspeed(0, 0.2) #wait until the copter slows down
|
||||
|
||||
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.set_rc(8, 1500) # switch to mid position
|
||||
self.set_rc(8, 1900) # auto execute vector AB
|
||||
self.wait_distance(17) # wait for it to finish
|
||||
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.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.set_rc(8, 1500) # switch to mid position
|
||||
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.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.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.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.change_mode('LOITER')
|
||||
j=j+1
|
||||
|
||||
self.do_RTL()
|
||||
|
||||
|
||||
def test_setting_modes_via_modeswitch(self):
|
||||
self.context_push()
|
||||
ex = None
|
||||
@ -3159,6 +3230,9 @@ class AutoTestCopter(AutoTest):
|
||||
"Test mavlink MANUAL_CONTROL",
|
||||
self.test_manual_control),
|
||||
|
||||
# Zigzag mode test
|
||||
("ZigZag", "Fly ZigZag Mode", self.fly_zigzag_mode),
|
||||
|
||||
("PosHoldTakeOff",
|
||||
"Fly POSHOLD takeoff",
|
||||
self.fly_poshold_takeoff),
|
||||
|
Loading…
Reference in New Issue
Block a user