Tools: autotest: Use the generic run_test.

If any of the tests throws an exception, it will be caught by the generic test function
that collects all errors and displays them before passing the result to the vehicle testcode.
Hence the name of the test and the exception that got raised get printed in a single
location. This nicely reduces code duplication.
This commit is contained in:
Karthik Desai 2018-04-27 20:21:53 +02:00 committed by Peter Barker
parent 7a20dd8b73
commit 40cd0cd17f
5 changed files with 293 additions and 722 deletions

View File

@ -10,6 +10,10 @@ import time
from common import AutoTest
from common import MsgRcvTimeoutException
from common import NotAchievedException
from common import PreconditionFailedException
from pysim import util
from pymavlink import mavutil
@ -194,7 +198,6 @@ class AutoTestRover(AutoTest):
def drive_square(self, side=50):
"""Drive a square, Driving N then E ."""
self.progress("TEST SQUARE")
success = True
# use LEARNING Mode
self.mavproxy.send('switch 5\n')
@ -202,57 +205,42 @@ class AutoTestRover(AutoTest):
# first aim north
self.progress("\nTurn right towards north")
if not self.reach_heading_manual(10):
success = False
self.reach_heading_manual(10)
# save bottom left corner of box as waypoint
self.progress("Save WP 1 & 2")
self.save_wp()
# pitch forward to fly north
self.progress("\nGoing north %u meters" % side)
if not self.reach_distance_manual(side):
success = False
self.reach_distance_manual(side)
# save top left corner of square as waypoint
self.progress("Save WP 3")
self.save_wp()
# roll right to fly east
self.progress("\nGoing east %u meters" % side)
if not self.reach_heading_manual(100):
success = False
if not self.reach_distance_manual(side):
success = False
self.reach_heading_manual(100)
self.reach_distance_manual(side)
# save top right corner of square as waypoint
self.progress("Save WP 4")
self.save_wp()
# pitch back to fly south
self.progress("\nGoing south %u meters" % side)
if not self.reach_heading_manual(190):
success = False
if not self.reach_distance_manual(side):
success = False
self.reach_heading_manual(190)
self.reach_distance_manual(side)
# save bottom right corner of square as waypoint
self.progress("Save WP 5")
self.save_wp()
# roll left to fly west
self.progress("\nGoing west %u meters" % side)
if not self.reach_heading_manual(280):
success = False
if not self.reach_distance_manual(side):
success = False
self.reach_heading_manual(280)
self.reach_distance_manual(side)
# save bottom left corner of square (should be near home) as waypoint
self.progress("Save WP 6")
self.save_wp()
return success
def drive_left_circuit(self):
"""Drive a left circuit, 50m on a side."""
self.mavproxy.send('switch 6\n')
@ -265,15 +253,12 @@ class AutoTestRover(AutoTest):
# hard left
self.progress("Starting turn %u" % i)
self.set_rc(1, 1000)
if not self.wait_heading(270 - (90*i), accuracy=10):
return False
self.wait_heading(270 - (90*i), accuracy=10)
self.set_rc(1, 1500)
self.progress("Starting leg %u" % i)
if not self.wait_distance(50, accuracy=7):
return False
self.wait_distance(50, accuracy=7)
self.set_rc(3, 1500)
self.progress("Circuit complete")
return True
# def test_throttle_failsafe(self, home, distance_min=10, side=60,
# timeout=300):
@ -338,11 +323,12 @@ class AutoTestRover(AutoTest):
self.mavproxy.send('switch 4\n') # auto mode
self.set_rc(3, 1500)
self.wait_mode('AUTO')
if not self.wait_waypoint(1, 4, max_dist=5):
return False
self.wait_waypoint(1, 4, max_dist=5)
self.wait_mode('HOLD')
self.progress("Mission OK")
return True
def drive_mission_rover1(self):
self.drive_mission(os.path.join(testdir, "rover1.txt"))
def do_get_banner(self):
self.mavproxy.send("long DO_SEND_BANNER 1\n")
@ -353,13 +339,12 @@ class AutoTestRover(AutoTest):
timeout=1)
if m is not None and "ArduRover" in m.text:
self.progress("banner received: %s" % m.text)
return True
return
if time.time() - start > 10:
break
self.progress("banner not received")
return False
raise MsgRcvTimeoutException()
def drive_brake_get_stopping_distance(self, speed):
# measure our stopping distance:
@ -421,14 +406,12 @@ class AutoTestRover(AutoTest):
(distance_with_brakes,
distance_without_brakes,
delta))
return False
else:
raise NotAchievedException()
self.progress(
"Brakes work (with=%0.2fm without=%0.2fm delta=%0.2fm)" %
(distance_with_brakes, distance_without_brakes, delta))
return True
def drive_rtl_mission(self):
mission_filepath = os.path.join(testdir,
"ArduRover-Missions",
@ -445,12 +428,12 @@ class AutoTestRover(AutoTest):
timeout=0.1)
if m is None:
self.progress("Did not receive NAV_CONTROLLER_OUTPUT message")
return False
raise MsgRcvTimeoutException()
wp_dist_min = 5
if m.wp_dist < wp_dist_min:
self.progress("Did not start at least 5 metres from destination")
return False
raise PreconditionFailedException()
self.progress("NAV_CONTROLLER_OUTPUT.wp_dist looks good (%u >= %u)" %
(m.wp_dist, wp_dist_min,))
@ -463,11 +446,10 @@ class AutoTestRover(AutoTest):
if home_distance > home_distance_max:
self.progress("Did not get home (%u metres distant > %u)" %
(home_distance, home_distance_max))
return False
raise NotAchievedException()
self.mavproxy.send('switch 6\n')
self.wait_mode('MANUAL')
self.progress("RTL Mission OK")
return True
def test_servorelayevents(self):
self.mavproxy.send("relay set 0 0\n")
@ -476,9 +458,8 @@ class AutoTestRover(AutoTest):
on = self.get_parameter("SIM_PIN_MASK")
if on == off:
self.progress("Pin mask unchanged after relay command")
return False
raise NotAchievedException()
self.progress("Pin mask changed after relay command")
return True
def autotest(self):
"""Autotest APMrover2 in SITL."""
@ -486,8 +467,7 @@ class AutoTestRover(AutoTest):
self.init()
self.progress("Started simulator")
failed = False
e = 'None'
self.fail_list = []
try:
self.progress("Waiting for a heartbeat with mavlink protocol %s" %
self.mav.WIRE_PROTOCOL_VERSION)
@ -503,75 +483,33 @@ class AutoTestRover(AutoTest):
self.wait_mode('MANUAL')
self.progress("Waiting reading for arm")
self.wait_ready_to_arm()
if not self.arm_vehicle():
self.progress("Failed to ARM")
failed = True
self.arm_vehicle()
self.progress("#")
self.progress("########## Drive an RTL mission ##########")
self.progress("#")
# Drive a square in learning mode
# self.reset_and_arm()
if not self.drive_rtl_mission():
self.progress("Failed RTL mission")
failed = True
self.run_test("Drive an RTL Mission", self.drive_rtl_mission)
self.progress("#")
self.progress("########## Drive a square and save WPs with CH7"
"switch ##########")
self.progress("#")
# Drive a square in learning mode
# self.reset_and_arm()
if not self.drive_square():
self.progress("Failed drive square")
failed = True
self.run_test("Learn/Drive Square with Ch7 option",
self.drive_square)
if not self.drive_mission(os.path.join(testdir, "rover1.txt")):
self.progress("Failed mission")
failed = True
self.run_test("Drive Mission %s" % "rover1.txt",
self.drive_mission_rover1)
if not self.drive_brake():
self.progress("Failed brake")
failed = True
self.run_test("Drive Brake", self.drive_brake)
if not self.disarm_vehicle():
self.progress("Failed to DISARM")
failed = True
self.run_test("Disarm Vehicle", self.disarm_vehicle)
# do not move this to be the first test. MAVProxy's dedupe
# function may bite you.
self.progress("Getting banner")
if not self.do_get_banner():
self.progress("FAILED: get banner")
failed = True
self.run_test("Get Banner", self.do_get_banner)
self.progress("Getting autopilot capabilities")
if not self.do_get_autopilot_capabilities():
self.progress("FAILED: get capabilities")
failed = True
self.run_test("Get Capabilities",
self.do_get_autopilot_capabilities)
self.progress("Setting mode via MAV_COMMAND_DO_SET_MODE")
if not self.do_set_mode_via_command_long():
failed = True
self.run_test("Set mode via MAV_COMMAND_DO_SET_MODE",
self.do_set_mode_via_command_long)
# test ServoRelayEvents:
self.progress("########## Test ServoRelayEvents ##########")
if not self.test_servorelayevents():
self.progress("Failed servo relay events")
failed = True
self.run_test("Test ServoRelayEvents",
self.test_servorelayevents)
# Throttle Failsafe
self.progress("#")
self.progress("########## Test Failsafe ##########")
self.progress("#")
# self.reset_and_arm()
# if not self.test_throttle_failsafe(HOME, distance_min=4):
# self.progress("Throttle failsafe failed")
# sucess = False
if not self.log_download(self.buildlogs_path("APMrover2-log.bin")):
self.progress("Failed log download")
failed = True
self.run_test("Download logs", lambda:
self.log_download(self.buildlogs_path("APMrover2-log.bin")))
# if not drive_left_circuit(self):
# self.progress("Failed left circuit")
# failed = True
@ -581,11 +519,11 @@ class AutoTestRover(AutoTest):
except pexpect.TIMEOUT as e:
self.progress("Failed with timeout")
failed = True
self.fail_list.append( ("*timeout*", None) )
self.close()
if failed:
self.progress("FAILED: %s" % e)
if len(self.fail_list):
self.progress("FAILED STEPS: %s" % self.fail_list)
return False
return True

File diff suppressed because it is too large Load Diff

View File

@ -11,6 +11,7 @@ from pymavlink import mavutil
from pysim import util
from common import AutoTest
from common import NotAchievedException
# get location of scripts
testdir = os.path.dirname(os.path.realpath(__file__))
@ -104,7 +105,6 @@ class AutoTestPlane(AutoTest):
def takeoff(self):
"""Takeoff get to 30m altitude."""
self.wait_ready_to_arm()
self.arm_vehicle()
@ -131,24 +131,21 @@ class AutoTestPlane(AutoTest):
self.set_rc(3, 2000)
# gain a bit of altitude
if not self.wait_altitude(self.homeloc.alt+150,
self.wait_altitude(self.homeloc.alt+150,
self.homeloc.alt+180,
timeout=30):
return False
timeout=30)
# level off
self.set_rc(2, 1500)
self.progress("TAKEOFF COMPLETE")
return True
def fly_left_circuit(self):
"""Fly a left circuit, 200m on a side."""
self.mavproxy.send('switch 4\n')
self.wait_mode('FBWA')
self.set_rc(3, 2000)
if not self.wait_level_flight():
return False
self.wait_level_flight()
self.progress("Flying left circuit")
# do 4 turns
@ -156,28 +153,23 @@ class AutoTestPlane(AutoTest):
# hard left
self.progress("Starting turn %u" % i)
self.set_rc(1, 1000)
if not self.wait_heading(270 - (90*i), accuracy=10):
return False
self.wait_heading(270 - (90*i), accuracy=10)
self.set_rc(1, 1500)
self.progress("Starting leg %u" % i)
if not self.wait_distance(100, accuracy=20):
return False
self.wait_distance(100, accuracy=20)
self.progress("Circuit complete")
return True
def fly_RTL(self):
"""Fly to home."""
self.progress("Flying home in RTL")
self.mavproxy.send('switch 2\n')
self.wait_mode('RTL')
if not self.wait_location(self.homeloc,
self.wait_location(self.homeloc,
accuracy=120,
target_altitude=self.homeloc.alt+100,
height_accuracy=20,
timeout=180):
return False
timeout=180)
self.progress("RTL Complete")
return True
def fly_LOITER(self, num_circles=4):
"""Loiter where we are."""
@ -190,10 +182,8 @@ class AutoTestPlane(AutoTest):
self.progress("Initial altitude %u\n" % initial_alt)
while num_circles > 0:
if not self.wait_heading(0, accuracy=10, timeout=60):
return False
if not self.wait_heading(180, accuracy=10, timeout=60):
return False
self.wait_heading(0, accuracy=10, timeout=60)
self.wait_heading(180, accuracy=10, timeout=60)
num_circles -= 1
self.progress("Loiter %u circles left" % num_circles)
@ -207,10 +197,9 @@ class AutoTestPlane(AutoTest):
if abs(final_alt - initial_alt) > 20:
self.progress("Failed to maintain altitude")
return False
raise NotAchievedException()
self.progress("Completed Loiter OK")
return True
def fly_CIRCLE(self, num_circles=1):
"""Circle where we are."""
@ -223,10 +212,8 @@ class AutoTestPlane(AutoTest):
self.progress("Initial altitude %u\n" % initial_alt)
while num_circles > 0:
if not self.wait_heading(0, accuracy=10, timeout=60):
return False
if not self.wait_heading(180, accuracy=10, timeout=60):
return False
self.wait_heading(0, accuracy=10, timeout=60)
self.wait_heading(180, accuracy=10, timeout=60)
num_circles -= 1
self.progress("CIRCLE %u circles left" % num_circles)
@ -240,10 +227,9 @@ class AutoTestPlane(AutoTest):
if abs(final_alt - initial_alt) > 20:
self.progress("Failed to maintain altitude")
return False
raise NotAchievedException()
self.progress("Completed CIRCLE OK")
return True
def wait_level_flight(self, accuracy=5, timeout=30):
"""Wait for level flight."""
@ -259,9 +245,9 @@ class AutoTestPlane(AutoTest):
self.progress("Roll=%.1f Pitch=%.1f" % (roll, pitch))
if math.fabs(roll) <= accuracy and math.fabs(pitch) <= accuracy:
self.progress("Attained level flight")
return True
return
self.progress("Failed to attain level flight")
return False
raise NotAchievedException()
def change_altitude(self, altitude, accuracy=30):
"""Get to a given altitude."""
@ -272,8 +258,7 @@ class AutoTestPlane(AutoTest):
self.set_rc(2, 2000)
else:
self.set_rc(2, 1000)
if not self.wait_altitude(altitude-accuracy/2, altitude+accuracy/2):
return False
self.wait_altitude(altitude-accuracy/2, altitude+accuracy/2)
self.set_rc(2, 1500)
self.progress("Reached target altitude at %u" %
self.mav.messages['VFR_HUD'].alt)
@ -283,8 +268,7 @@ class AutoTestPlane(AutoTest):
"""Fly a left axial roll."""
# full throttle!
self.set_rc(3, 2000)
if not self.change_altitude(self.homeloc.alt+300):
return False
self.change_altitude(self.homeloc.alt+300)
# fly the roll in manual
self.mavproxy.send('switch 6\n')
@ -293,15 +277,13 @@ class AutoTestPlane(AutoTest):
while count > 0:
self.progress("Starting roll")
self.set_rc(1, 1000)
if not self.wait_roll(-150, accuracy=90):
try:
self.wait_roll(-150, accuracy=90)
self.wait_roll(150, accuracy=90)
self.wait_roll(0, accuracy=90)
except Exception as e:
self.set_rc(1,1500)
return False
if not self.wait_roll(150, accuracy=90):
self.set_rc(1, 1500)
return False
if not self.wait_roll(0, accuracy=90):
self.set_rc(1, 1500)
return False
raise e
count -= 1
# back to FBWA
@ -315,9 +297,7 @@ class AutoTestPlane(AutoTest):
"""Fly a inside loop."""
# full throttle!
self.set_rc(3, 2000)
if not self.change_altitude(self.homeloc.alt+300):
return False
self.change_altitude(self.homeloc.alt+300)
# fly the loop in manual
self.mavproxy.send('switch 6\n')
self.wait_mode('MANUAL')
@ -325,10 +305,8 @@ class AutoTestPlane(AutoTest):
while count > 0:
self.progress("Starting loop")
self.set_rc(2, 1000)
if not self.wait_pitch(-60, accuracy=20):
return False
if not self.wait_pitch(0, accuracy=20):
return False
self.wait_pitch(-60, accuracy=20)
self.wait_pitch(0, accuracy=20)
count -= 1
# back to FBWA
@ -343,8 +321,7 @@ class AutoTestPlane(AutoTest):
# full throttle!
self.set_rc(3, 2000)
self.set_rc(2, 1300)
if not self.change_altitude(self.homeloc.alt+300):
return False
self.change_altitude(self.homeloc.alt+300)
self.set_rc(2, 1500)
self.mavproxy.send("mode STABILIZE\n")
@ -354,17 +331,13 @@ class AutoTestPlane(AutoTest):
while count > 0:
self.progress("Starting roll")
self.set_rc(1, 2000)
if not self.wait_roll(-150, accuracy=90):
return False
if not self.wait_roll(150, accuracy=90):
return False
if not self.wait_roll(0, accuracy=90):
return False
self.wait_roll(-150, accuracy=90)
self.wait_roll(150, accuracy=90)
self.wait_roll(0, accuracy=90)
count -= 1
self.set_rc(1, 1500)
if not self.wait_roll(0, accuracy=5):
return False
self.wait_roll(0, accuracy=5)
# back to FBWA
self.mavproxy.send('mode FBWA\n')
@ -377,8 +350,7 @@ class AutoTestPlane(AutoTest):
# full throttle!
self.set_rc(3, 2000)
self.set_rc(2, 1300)
if not self.change_altitude(self.homeloc.alt+300):
return False
self.change_altitude(self.homeloc.alt+300)
self.set_rc(2, 1500)
self.mavproxy.send("mode ACRO\n")
@ -388,12 +360,9 @@ class AutoTestPlane(AutoTest):
while count > 0:
self.progress("Starting roll")
self.set_rc(1, 1000)
if not self.wait_roll(-150, accuracy=90):
return False
if not self.wait_roll(150, accuracy=90):
return False
if not self.wait_roll(0, accuracy=90):
return False
self.wait_roll(-150, accuracy=90)
self.wait_roll(150, accuracy=90)
self.wait_roll(0, accuracy=90)
count -= 1
self.set_rc(1, 1500)
@ -410,10 +379,8 @@ class AutoTestPlane(AutoTest):
while count > 0:
self.progress("Starting loop")
self.set_rc(2, 1000)
if not self.wait_pitch(-60, accuracy=20):
return False
if not self.wait_pitch(0, accuracy=20):
return False
self.wait_pitch(-60, accuracy=20)
self.wait_pitch(0, accuracy=20)
count -= 1
self.set_rc(2, 1500)
@ -447,13 +414,14 @@ class AutoTestPlane(AutoTest):
# hard left
self.progress("Starting turn %u" % i)
self.set_rc(1, 1800)
if not self.wait_heading(0 + (90*i), accuracy=20, timeout=60):
try:
self.wait_heading(0 + (90*i), accuracy=20, timeout=60)
except Exception as e:
self.set_rc(1, 1500)
return False
raise e
self.set_rc(1, 1500)
self.progress("Starting leg %u" % i)
if not self.wait_distance(100, accuracy=20):
return False
self.wait_distance(100, accuracy=20)
self.progress("Circuit complete")
self.progress("Flying rudder left circuit")
@ -462,13 +430,14 @@ class AutoTestPlane(AutoTest):
# hard left
self.progress("Starting turn %u" % i)
self.set_rc(4, 1900)
if not self.wait_heading(360 - (90*i), accuracy=20, timeout=60):
try:
self.wait_heading(360 - (90*i), accuracy=20, timeout=60)
except Exception as e:
self.set_rc(4, 1500)
return False
raise e
self.set_rc(4, 1500)
self.progress("Starting leg %u" % i)
if not self.wait_distance(100, accuracy=20):
return False
self.wait_distance(100, accuracy=20)
self.progress("Circuit complete")
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
@ -482,7 +451,7 @@ class AutoTestPlane(AutoTest):
if abs(final_alt - initial_alt) > 20:
self.progress("Failed to maintain altitude")
return False
raise NotAchievedException()
return self.wait_level_flight()
@ -495,22 +464,17 @@ class AutoTestPlane(AutoTest):
self.mavproxy.expect('Requesting [0-9]+ waypoints')
self.mavproxy.send('switch 1\n') # auto mode
self.wait_mode('AUTO')
if not self.wait_waypoint(1, 7, max_dist=60):
return False
if not self.wait_groundspeed(0, 0.5, timeout=60):
return False
self.wait_waypoint(1, 7, max_dist=60)
self.wait_groundspeed(0, 0.5, timeout=60)
self.mavproxy.expect("Auto disarmed")
self.progress("Mission OK")
return True
def autotest(self):
"""Autotest ArduPlane in SITL."""
if not self.hasInit:
self.init()
failed = False
fail_list = []
e = 'None'
self.fail_list = []
try:
self.progress("Waiting for a heartbeat with mavlink protocol %s"
% self.mav.WIRE_PROTOCOL_VERSION)
@ -526,69 +490,42 @@ class AutoTestPlane(AutoTest):
self.mav.wait_gps_fix()
self.homeloc = self.mav.location()
self.progress("Home location: %s" % self.homeloc)
if not self.takeoff():
self.progress("Failed takeoff")
failed = True
fail_list.append("takeoff")
if not self.fly_left_circuit():
self.progress("Failed left circuit")
failed = True
fail_list.append("left_circuit")
if not self.axial_left_roll(1):
self.progress("Failed left roll")
failed = True
fail_list.append("left_roll")
if not self.inside_loop():
self.progress("Failed inside loop")
failed = True
fail_list.append("inside_loop")
if not self.test_stabilize():
self.progress("Failed stabilize test")
failed = True
fail_list.append("stabilize")
if not self.test_acro():
self.progress("Failed ACRO test")
failed = True
fail_list.append("acro")
if not self.test_FBWB():
self.progress("Failed FBWB test")
failed = True
fail_list.append("fbwb")
if not self.test_FBWB(mode='CRUISE'):
self.progress("Failed CRUISE test")
failed = True
fail_list.append("cruise")
if not self.fly_RTL():
self.progress("Failed RTL")
failed = True
fail_list.append("RTL")
if not self.fly_LOITER():
self.progress("Failed LOITER")
failed = True
fail_list.append("LOITER")
if not self.fly_CIRCLE():
self.progress("Failed CIRCLE")
failed = True
fail_list.append("LOITER")
if not self.fly_mission(os.path.join(testdir, "ap1.txt"),
self.run_test("Takeoff", self.takeoff)
self.run_test("Fly left circuit", self.fly_left_circuit)
self.run_test("Left roll", lambda: self.axial_left_roll(1))
self.run_test("Inside loop", self.inside_loop)
self.run_test("Stablize test", self.test_stabilize)
self.run_test("ACRO test", self.test_acro)
self.run_test("FBWB test", self.test_FBWB)
self.run_test("CRUISE test", lambda: self.test_FBWB(mode='CRUISE'))
self.run_test("RTL test", self.fly_RTL)
self.run_test("LOITER test", self.fly_LOITER)
self.run_test("CIRCLE test", self.fly_CIRCLE)
self.run_test("Mission test", lambda: self.fly_mission(os.path.join(testdir, "ap1.txt"),
height_accuracy=10,
target_altitude=self.homeloc.alt+100):
self.progress("Failed mission")
failed = True
fail_list.append("mission")
if not self.log_download(self.buildlogs_path("ArduPlane-log.bin")):
self.progress("Failed log download")
failed = True
fail_list.append("log_download")
target_altitude=self.homeloc.alt+100))
self.run_test("Log download", lambda: self.log_download(self.buildlogs_path("ArduPlane-log.bin")))
except pexpect.TIMEOUT as e:
self.progress("Failed with timeout")
failed = True
fail_list.append("timeout")
self.fail_list.append("timeout")
self.close()
if failed:
self.progress("FAILED: %s" % e)
self.progress("Fail list: %s" % fail_list)
if len(self.fail_list):
self.progress("FAILED: %s" % self.fail_list)
return False
return True

View File

@ -103,39 +103,27 @@ class AutoTestSub(AutoTest):
self.set_rc(5, 1600)
self.set_rc(6, 1550)
if not self.wait_distance(50, accuracy=7, timeout=200):
return False
self.wait_distance(50, accuracy=7, timeout=200)
self.set_rc(4, 1550)
if not self.wait_heading(0):
return False
self.wait_heading(0)
self.set_rc(4, 1500)
if not self.wait_distance(50, accuracy=7, timeout=100):
return False
self.wait_distance(50, accuracy=7, timeout=100)
self.set_rc(4, 1550)
if not self.wait_heading(0):
return False
self.wait_heading(0)
self.set_rc(4, 1500)
self.set_rc(5, 1500)
self.set_rc(6, 1100)
if not self.wait_distance(75, accuracy=7, timeout=100):
return False
self.wait_distance(75, accuracy=7, timeout=100)
self.set_rc_default()
self.disarm_vehicle()
self.progress("Manual dive OK")
return True
def dive_mission(self, filename):
self.progress("Executing mission %s" % filename)
self.mavproxy.send('wp load %s\n' % filename)
self.mavproxy.expect('Flight plan received')
@ -143,28 +131,23 @@ class AutoTestSub(AutoTest):
self.mavproxy.expect('Saved [0-9]+ waypoints')
self.set_rc_default()
if not self.arm_vehicle():
self.progress("Failed to ARM")
return False
self.arm_vehicle()
self.mavproxy.send('mode auto\n')
self.wait_mode('AUTO')
if not self.wait_waypoint(1, 5, max_dist=5):
return False
self.wait_waypoint(1, 5, max_dist=5)
self.disarm_vehicle()
self.progress("Mission OK")
return True
def autotest(self):
"""Autotest ArduSub in SITL."""
if not self.hasInit:
self.init()
failed = False
e = 'None'
self.fail_list = []
try:
self.progress("Waiting for a heartbeat with mavlink protocol %s"
% self.mav.WIRE_PROTOCOL_VERSION)
@ -179,25 +162,22 @@ class AutoTestSub(AutoTest):
self.homeloc = self.mav.location()
self.progress("Home location: %s" % self.homeloc)
self.set_rc_default()
if not self.arm_vehicle():
self.progress("Failed to ARM")
failed = True
if not self.dive_manual():
self.progress("Failed manual dive")
failed = True
if not self.dive_mission(os.path.join(testdir, "sub_mission.txt")):
self.progress("Failed auto mission")
failed = True
if not self.log_download(self.buildlogs_path("ArduSub-log.bin")):
self.progress("Failed log download")
failed = True
self.run_test("Arm vehicle", self.arm_vehicle)
self.run_test("Dive manual", self.dive_manual)
self.run_test("Dive mission", lambda: self.dive_mission(os.path.join(testdir, "sub_mission.txt")))
self.run_test("Log download", lambda: self.log_download(self.buildlogs_path("ArduSub-log.bin")))
except pexpect.TIMEOUT as e:
self.progress("Failed with timeout")
failed = True
self.fail_list.append("Failed with timeout")
self.close()
if failed:
self.progress("FAILED: %s" % e)
if len(self.fail_list):
self.progress("FAILED: %s" % self.fail_list)
return False
return True

View File

@ -134,25 +134,24 @@ class AutoTestQuadPlane(AutoTest):
self.mavproxy.expect('Requesting [0-9]+ waypoints')
self.mavproxy.send('mode AUTO\n')
self.wait_mode('AUTO')
if not self.wait_waypoint(1, 19, max_dist=60, timeout=1200):
return False
self.wait_waypoint(1, 19, max_dist=60, timeout=1200)
self.mavproxy.expect('DISARMED')
# wait for blood sample here
self.mavproxy.send('wp set 20\n')
self.arm_vehicle()
if not self.wait_waypoint(20, 34, max_dist=60, timeout=1200):
return False
self.wait_waypoint(20, 34, max_dist=60, timeout=1200)
self.mavproxy.expect('DISARMED')
self.progress("Mission OK")
return True
def autotest(self):
"""Autotest QuadPlane in SITL."""
if not self.hasInit:
self.init()
failed = False
e = 'None'
self.fail_list = []
try:
self.progress("Waiting for a heartbeat with mavlink protocol %s"
% self.mav.WIRE_PROTOCOL_VERSION)
@ -174,16 +173,15 @@ class AutoTestQuadPlane(AutoTest):
m = os.path.join(testdir, "ArduPlane-Missions/Dalby-OBC2016.txt")
f = os.path.join(testdir,
"ArduPlane-Missions/Dalby-OBC2016-fence.txt")
if not self.fly_mission(m, f):
self.progress("Failed mission")
failed = True
self.run_test("Mission", lambda: self.fly_mission(m, f))
except pexpect.TIMEOUT as e:
self.progress("Failed with timeout")
failed = True
self.fail_list.append("Failed with timeout")
self.close()
if failed:
self.progress("FAILED: %s" % e)
if len(self.fail_list):
self.progress("FAILED: %s" % self.fail_list)
return False
return True