mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
autotest: reset mission on takeoff for quadplanes
This commit is contained in:
parent
6bf9556612
commit
4aaa0ce6b2
@ -6542,6 +6542,7 @@ Also, ignores heartbeats not from our target system'''
|
|||||||
try:
|
try:
|
||||||
self.check_rc_defaults()
|
self.check_rc_defaults()
|
||||||
self.change_mode(self.default_mode())
|
self.change_mode(self.default_mode())
|
||||||
|
self.set_current_waypoint(0, check_afterwards=False)
|
||||||
self.drain_mav()
|
self.drain_mav()
|
||||||
self.drain_all_pexpects()
|
self.drain_all_pexpects()
|
||||||
|
|
||||||
|
@ -446,6 +446,7 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
|
|
||||||
def takeoff(self, height, mode):
|
def takeoff(self, height, mode):
|
||||||
"""climb to specified height and set throttle to 1500"""
|
"""climb to specified height and set throttle to 1500"""
|
||||||
|
self.set_current_waypoint(0, check_afterwards=False)
|
||||||
self.change_mode(mode)
|
self.change_mode(mode)
|
||||||
self.wait_ready_to_arm()
|
self.wait_ready_to_arm()
|
||||||
self.arm_vehicle()
|
self.arm_vehicle()
|
||||||
|
Loading…
Reference in New Issue
Block a user