mirror of https://github.com/ArduPilot/ardupilot
Tools: autotest: remove needless wrappers, initialisation etc around guided-submode test
Also disable disarm delay due to autotest mavlink traffic issues
This commit is contained in:
parent
57ab496a1c
commit
b450355ff6
|
@ -2318,16 +2318,12 @@ class AutoTestCopter(AutoTest):
|
|||
def fly_guided_change_submode(self):
|
||||
""""Ensure we can move around in guided after a takeoff command."""
|
||||
|
||||
self.context_push()
|
||||
|
||||
ex = None
|
||||
try:
|
||||
'''start by disabling GCS failsafe, otherwise we immediately disarm
|
||||
due to (apparently) not receiving traffic from the GCS for
|
||||
too long. This is probably a function of --speedup'''
|
||||
self.set_parameter("FS_GCS_ENABLE", 0)
|
||||
self.mavproxy.send('mode guided\n') # stabilize mode
|
||||
self.wait_mode('GUIDED')
|
||||
self.set_parameter("DISARM_DELAY", 0) # until traffic problems are fixed
|
||||
self.change_mode("GUIDED")
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
|
||||
|
@ -2344,21 +2340,7 @@ class AutoTestCopter(AutoTest):
|
|||
self.fly_guided_stop()
|
||||
self.fly_guided_move_local(5, 5, 10)
|
||||
|
||||
self.progress("Landing")
|
||||
self.mavproxy.send('switch 2\n') # land mode
|
||||
self.wait_mode('LAND')
|
||||
self.mav.motors_disarmed_wait()
|
||||
|
||||
except Exception as e:
|
||||
self.progress("Exception caught")
|
||||
ex = e
|
||||
|
||||
self.context_pop()
|
||||
self.zero_throttle()
|
||||
self.reboot_sitl()
|
||||
|
||||
if ex is not None:
|
||||
raise ex
|
||||
self.do_RTL()
|
||||
|
||||
def test_gripper_mission(self):
|
||||
self.context_push()
|
||||
|
|
Loading…
Reference in New Issue