mirror of https://github.com/ArduPilot/ardupilot
Tools: autotest: make fly_avc_test a little more self-contained
This commit is contained in:
parent
9767c74311
commit
4ae8595da3
|
@ -1125,6 +1125,15 @@ class AutoTestCopter(AutoTest):
|
|||
|
||||
# fly_avc_test - fly AVC mission
|
||||
def fly_avc_test(self):
|
||||
# Arm
|
||||
self.mavproxy.send('switch 6\n') # stabilize mode
|
||||
self.wait_mode('STABILIZE')
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
self.arm_vehicle()
|
||||
self.progress("Raising rotor speed")
|
||||
self.set_rc(8, 2000)
|
||||
|
||||
# upload mission from file
|
||||
self.progress("# Load copter_AVC2013_mission")
|
||||
# load the waypoint count
|
||||
|
@ -1154,6 +1163,9 @@ class AutoTestCopter(AutoTest):
|
|||
self.mav.motors_disarmed_wait()
|
||||
self.progress("MOTORS DISARMED OK")
|
||||
|
||||
self.progress("Lowering rotor speed")
|
||||
self.set_rc(8, 1000)
|
||||
|
||||
self.progress("AVC mission completed: passed!")
|
||||
|
||||
def fly_motor_fail(self, fail_servo=0, fail_mul=0.0, holdtime=30):
|
||||
|
@ -2661,18 +2673,11 @@ class AutoTestCopter(AutoTest):
|
|||
self.mavproxy.send('switch 6\n') # stabilize mode
|
||||
self.wait_mode('STABILIZE')
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
self.run_test("Arm features", self.test_arm_feature)
|
||||
|
||||
# Arm
|
||||
self.run_test("Arm motors", self.arm_vehicle)
|
||||
self.progress("Raising rotor speed")
|
||||
self.set_rc(8, 2000)
|
||||
|
||||
self.run_test("Fly AVC mission", self.fly_avc_test)
|
||||
|
||||
self.progress("Lowering rotor speed")
|
||||
self.set_rc(8, 1000)
|
||||
|
||||
# mission ends with disarm so should be ok to download logs now
|
||||
self.run_test("log download",
|
||||
lambda: self.log_download(
|
||||
|
|
Loading…
Reference in New Issue