mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: add a test for VTOL land spiral code
This commit is contained in:
parent
77e63da4b3
commit
2b2bd2b85b
@ -0,0 +1,6 @@
|
|||||||
|
QGC WPL 110
|
||||||
|
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -27.274439 151.290064 343.100006 1
|
||||||
|
1 0 3 84 0.000000 0.000000 0.000000 0.000000 -27.274449 151.290081 20.000000 1
|
||||||
|
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -27.264608 151.286680 198.659988 1
|
||||||
|
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -27.270692 151.290099 200.000000 1
|
||||||
|
4 0 3 85 1.000000 0.000000 0.000000 0.000000 -27.274428 151.290091 30.000000 1
|
@ -1096,6 +1096,13 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
self.wait_disarmed(timeout=120) # give quadplane a long time to land
|
self.wait_disarmed(timeout=120) # give quadplane a long time to land
|
||||||
self.progress("Mission OK")
|
self.progress("Mission OK")
|
||||||
|
|
||||||
|
def VTOLLandSpiral(self):
|
||||||
|
'''check spiral-to-alt option for landing'''
|
||||||
|
self.fly_mission('mission.txt')
|
||||||
|
self.set_parameter('WP_LOITER_RAD', -self.get_parameter('WP_LOITER_RAD'))
|
||||||
|
self.set_current_waypoint(0, check_afterwards=False)
|
||||||
|
self.fly_mission('mission.txt')
|
||||||
|
|
||||||
def tests(self):
|
def tests(self):
|
||||||
'''return list of all tests'''
|
'''return list of all tests'''
|
||||||
|
|
||||||
@ -1119,5 +1126,6 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
self.Ship,
|
self.Ship,
|
||||||
self.MAV_CMD_NAV_LOITER_TO_ALT,
|
self.MAV_CMD_NAV_LOITER_TO_ALT,
|
||||||
self.LoiterAltQLand,
|
self.LoiterAltQLand,
|
||||||
|
self.VTOLLandSpiral,
|
||||||
])
|
])
|
||||||
return ret
|
return ret
|
||||||
|
Loading…
Reference in New Issue
Block a user