mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
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:
parent
7a20dd8b73
commit
40cd0cd17f
@ -10,6 +10,10 @@ import time
|
|||||||
|
|
||||||
from common import AutoTest
|
from common import AutoTest
|
||||||
|
|
||||||
|
from common import MsgRcvTimeoutException
|
||||||
|
from common import NotAchievedException
|
||||||
|
from common import PreconditionFailedException
|
||||||
|
|
||||||
from pysim import util
|
from pysim import util
|
||||||
|
|
||||||
from pymavlink import mavutil
|
from pymavlink import mavutil
|
||||||
@ -194,7 +198,6 @@ class AutoTestRover(AutoTest):
|
|||||||
def drive_square(self, side=50):
|
def drive_square(self, side=50):
|
||||||
"""Drive a square, Driving N then E ."""
|
"""Drive a square, Driving N then E ."""
|
||||||
self.progress("TEST SQUARE")
|
self.progress("TEST SQUARE")
|
||||||
success = True
|
|
||||||
|
|
||||||
# use LEARNING Mode
|
# use LEARNING Mode
|
||||||
self.mavproxy.send('switch 5\n')
|
self.mavproxy.send('switch 5\n')
|
||||||
@ -202,57 +205,42 @@ class AutoTestRover(AutoTest):
|
|||||||
|
|
||||||
# first aim north
|
# first aim north
|
||||||
self.progress("\nTurn right towards north")
|
self.progress("\nTurn right towards north")
|
||||||
if not self.reach_heading_manual(10):
|
self.reach_heading_manual(10)
|
||||||
success = False
|
|
||||||
|
|
||||||
# save bottom left corner of box as waypoint
|
# save bottom left corner of box as waypoint
|
||||||
self.progress("Save WP 1 & 2")
|
self.progress("Save WP 1 & 2")
|
||||||
self.save_wp()
|
self.save_wp()
|
||||||
|
|
||||||
# pitch forward to fly north
|
# pitch forward to fly north
|
||||||
self.progress("\nGoing north %u meters" % side)
|
self.progress("\nGoing north %u meters" % side)
|
||||||
if not self.reach_distance_manual(side):
|
self.reach_distance_manual(side)
|
||||||
success = False
|
|
||||||
|
|
||||||
# save top left corner of square as waypoint
|
# save top left corner of square as waypoint
|
||||||
self.progress("Save WP 3")
|
self.progress("Save WP 3")
|
||||||
self.save_wp()
|
self.save_wp()
|
||||||
|
|
||||||
# roll right to fly east
|
# roll right to fly east
|
||||||
self.progress("\nGoing east %u meters" % side)
|
self.progress("\nGoing east %u meters" % side)
|
||||||
if not self.reach_heading_manual(100):
|
self.reach_heading_manual(100)
|
||||||
success = False
|
self.reach_distance_manual(side)
|
||||||
if not self.reach_distance_manual(side):
|
|
||||||
success = False
|
|
||||||
|
|
||||||
# save top right corner of square as waypoint
|
# save top right corner of square as waypoint
|
||||||
self.progress("Save WP 4")
|
self.progress("Save WP 4")
|
||||||
self.save_wp()
|
self.save_wp()
|
||||||
|
|
||||||
# pitch back to fly south
|
# pitch back to fly south
|
||||||
self.progress("\nGoing south %u meters" % side)
|
self.progress("\nGoing south %u meters" % side)
|
||||||
if not self.reach_heading_manual(190):
|
self.reach_heading_manual(190)
|
||||||
success = False
|
self.reach_distance_manual(side)
|
||||||
if not self.reach_distance_manual(side):
|
|
||||||
success = False
|
|
||||||
|
|
||||||
# save bottom right corner of square as waypoint
|
# save bottom right corner of square as waypoint
|
||||||
self.progress("Save WP 5")
|
self.progress("Save WP 5")
|
||||||
self.save_wp()
|
self.save_wp()
|
||||||
|
|
||||||
# roll left to fly west
|
# roll left to fly west
|
||||||
self.progress("\nGoing west %u meters" % side)
|
self.progress("\nGoing west %u meters" % side)
|
||||||
if not self.reach_heading_manual(280):
|
self.reach_heading_manual(280)
|
||||||
success = False
|
self.reach_distance_manual(side)
|
||||||
if not self.reach_distance_manual(side):
|
|
||||||
success = False
|
|
||||||
|
|
||||||
# save bottom left corner of square (should be near home) as waypoint
|
# save bottom left corner of square (should be near home) as waypoint
|
||||||
self.progress("Save WP 6")
|
self.progress("Save WP 6")
|
||||||
self.save_wp()
|
self.save_wp()
|
||||||
|
|
||||||
return success
|
|
||||||
|
|
||||||
def drive_left_circuit(self):
|
def drive_left_circuit(self):
|
||||||
"""Drive a left circuit, 50m on a side."""
|
"""Drive a left circuit, 50m on a side."""
|
||||||
self.mavproxy.send('switch 6\n')
|
self.mavproxy.send('switch 6\n')
|
||||||
@ -265,15 +253,12 @@ class AutoTestRover(AutoTest):
|
|||||||
# hard left
|
# hard left
|
||||||
self.progress("Starting turn %u" % i)
|
self.progress("Starting turn %u" % i)
|
||||||
self.set_rc(1, 1000)
|
self.set_rc(1, 1000)
|
||||||
if not self.wait_heading(270 - (90*i), accuracy=10):
|
self.wait_heading(270 - (90*i), accuracy=10)
|
||||||
return False
|
|
||||||
self.set_rc(1, 1500)
|
self.set_rc(1, 1500)
|
||||||
self.progress("Starting leg %u" % i)
|
self.progress("Starting leg %u" % i)
|
||||||
if not self.wait_distance(50, accuracy=7):
|
self.wait_distance(50, accuracy=7)
|
||||||
return False
|
|
||||||
self.set_rc(3, 1500)
|
self.set_rc(3, 1500)
|
||||||
self.progress("Circuit complete")
|
self.progress("Circuit complete")
|
||||||
return True
|
|
||||||
|
|
||||||
# def test_throttle_failsafe(self, home, distance_min=10, side=60,
|
# def test_throttle_failsafe(self, home, distance_min=10, side=60,
|
||||||
# timeout=300):
|
# timeout=300):
|
||||||
@ -338,11 +323,12 @@ class AutoTestRover(AutoTest):
|
|||||||
self.mavproxy.send('switch 4\n') # auto mode
|
self.mavproxy.send('switch 4\n') # auto mode
|
||||||
self.set_rc(3, 1500)
|
self.set_rc(3, 1500)
|
||||||
self.wait_mode('AUTO')
|
self.wait_mode('AUTO')
|
||||||
if not self.wait_waypoint(1, 4, max_dist=5):
|
self.wait_waypoint(1, 4, max_dist=5)
|
||||||
return False
|
|
||||||
self.wait_mode('HOLD')
|
self.wait_mode('HOLD')
|
||||||
self.progress("Mission OK")
|
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):
|
def do_get_banner(self):
|
||||||
self.mavproxy.send("long DO_SEND_BANNER 1\n")
|
self.mavproxy.send("long DO_SEND_BANNER 1\n")
|
||||||
@ -353,13 +339,12 @@ class AutoTestRover(AutoTest):
|
|||||||
timeout=1)
|
timeout=1)
|
||||||
if m is not None and "ArduRover" in m.text:
|
if m is not None and "ArduRover" in m.text:
|
||||||
self.progress("banner received: %s" % m.text)
|
self.progress("banner received: %s" % m.text)
|
||||||
return True
|
return
|
||||||
if time.time() - start > 10:
|
if time.time() - start > 10:
|
||||||
break
|
break
|
||||||
|
|
||||||
self.progress("banner not received")
|
self.progress("banner not received")
|
||||||
|
raise MsgRcvTimeoutException()
|
||||||
return False
|
|
||||||
|
|
||||||
def drive_brake_get_stopping_distance(self, speed):
|
def drive_brake_get_stopping_distance(self, speed):
|
||||||
# measure our stopping distance:
|
# measure our stopping distance:
|
||||||
@ -421,13 +406,11 @@ class AutoTestRover(AutoTest):
|
|||||||
(distance_with_brakes,
|
(distance_with_brakes,
|
||||||
distance_without_brakes,
|
distance_without_brakes,
|
||||||
delta))
|
delta))
|
||||||
return False
|
raise NotAchievedException()
|
||||||
else:
|
|
||||||
self.progress(
|
|
||||||
"Brakes work (with=%0.2fm without=%0.2fm delta=%0.2fm)" %
|
|
||||||
(distance_with_brakes, distance_without_brakes, delta))
|
|
||||||
|
|
||||||
return True
|
self.progress(
|
||||||
|
"Brakes work (with=%0.2fm without=%0.2fm delta=%0.2fm)" %
|
||||||
|
(distance_with_brakes, distance_without_brakes, delta))
|
||||||
|
|
||||||
def drive_rtl_mission(self):
|
def drive_rtl_mission(self):
|
||||||
mission_filepath = os.path.join(testdir,
|
mission_filepath = os.path.join(testdir,
|
||||||
@ -445,12 +428,12 @@ class AutoTestRover(AutoTest):
|
|||||||
timeout=0.1)
|
timeout=0.1)
|
||||||
if m is None:
|
if m is None:
|
||||||
self.progress("Did not receive NAV_CONTROLLER_OUTPUT message")
|
self.progress("Did not receive NAV_CONTROLLER_OUTPUT message")
|
||||||
return False
|
raise MsgRcvTimeoutException()
|
||||||
|
|
||||||
wp_dist_min = 5
|
wp_dist_min = 5
|
||||||
if m.wp_dist < wp_dist_min:
|
if m.wp_dist < wp_dist_min:
|
||||||
self.progress("Did not start at least 5 metres from destination")
|
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)" %
|
self.progress("NAV_CONTROLLER_OUTPUT.wp_dist looks good (%u >= %u)" %
|
||||||
(m.wp_dist, wp_dist_min,))
|
(m.wp_dist, wp_dist_min,))
|
||||||
@ -463,11 +446,10 @@ class AutoTestRover(AutoTest):
|
|||||||
if home_distance > home_distance_max:
|
if home_distance > home_distance_max:
|
||||||
self.progress("Did not get home (%u metres distant > %u)" %
|
self.progress("Did not get home (%u metres distant > %u)" %
|
||||||
(home_distance, home_distance_max))
|
(home_distance, home_distance_max))
|
||||||
return False
|
raise NotAchievedException()
|
||||||
self.mavproxy.send('switch 6\n')
|
self.mavproxy.send('switch 6\n')
|
||||||
self.wait_mode('MANUAL')
|
self.wait_mode('MANUAL')
|
||||||
self.progress("RTL Mission OK")
|
self.progress("RTL Mission OK")
|
||||||
return True
|
|
||||||
|
|
||||||
def test_servorelayevents(self):
|
def test_servorelayevents(self):
|
||||||
self.mavproxy.send("relay set 0 0\n")
|
self.mavproxy.send("relay set 0 0\n")
|
||||||
@ -476,9 +458,8 @@ class AutoTestRover(AutoTest):
|
|||||||
on = self.get_parameter("SIM_PIN_MASK")
|
on = self.get_parameter("SIM_PIN_MASK")
|
||||||
if on == off:
|
if on == off:
|
||||||
self.progress("Pin mask unchanged after relay command")
|
self.progress("Pin mask unchanged after relay command")
|
||||||
return False
|
raise NotAchievedException()
|
||||||
self.progress("Pin mask changed after relay command")
|
self.progress("Pin mask changed after relay command")
|
||||||
return True
|
|
||||||
|
|
||||||
def autotest(self):
|
def autotest(self):
|
||||||
"""Autotest APMrover2 in SITL."""
|
"""Autotest APMrover2 in SITL."""
|
||||||
@ -486,8 +467,7 @@ class AutoTestRover(AutoTest):
|
|||||||
self.init()
|
self.init()
|
||||||
self.progress("Started simulator")
|
self.progress("Started simulator")
|
||||||
|
|
||||||
failed = False
|
self.fail_list = []
|
||||||
e = 'None'
|
|
||||||
try:
|
try:
|
||||||
self.progress("Waiting for a heartbeat with mavlink protocol %s" %
|
self.progress("Waiting for a heartbeat with mavlink protocol %s" %
|
||||||
self.mav.WIRE_PROTOCOL_VERSION)
|
self.mav.WIRE_PROTOCOL_VERSION)
|
||||||
@ -503,75 +483,33 @@ class AutoTestRover(AutoTest):
|
|||||||
self.wait_mode('MANUAL')
|
self.wait_mode('MANUAL')
|
||||||
self.progress("Waiting reading for arm")
|
self.progress("Waiting reading for arm")
|
||||||
self.wait_ready_to_arm()
|
self.wait_ready_to_arm()
|
||||||
if not self.arm_vehicle():
|
self.arm_vehicle()
|
||||||
self.progress("Failed to ARM")
|
|
||||||
failed = True
|
|
||||||
|
|
||||||
self.progress("#")
|
self.run_test("Drive an RTL Mission", self.drive_rtl_mission)
|
||||||
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.progress("#")
|
self.run_test("Learn/Drive Square with Ch7 option",
|
||||||
self.progress("########## Drive a square and save WPs with CH7"
|
self.drive_square)
|
||||||
"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
|
|
||||||
|
|
||||||
if not self.drive_mission(os.path.join(testdir, "rover1.txt")):
|
self.run_test("Drive Mission %s" % "rover1.txt",
|
||||||
self.progress("Failed mission")
|
self.drive_mission_rover1)
|
||||||
failed = True
|
|
||||||
|
|
||||||
if not self.drive_brake():
|
self.run_test("Drive Brake", self.drive_brake)
|
||||||
self.progress("Failed brake")
|
|
||||||
failed = True
|
|
||||||
|
|
||||||
if not self.disarm_vehicle():
|
self.run_test("Disarm Vehicle", self.disarm_vehicle)
|
||||||
self.progress("Failed to DISARM")
|
|
||||||
failed = True
|
|
||||||
|
|
||||||
# do not move this to be the first test. MAVProxy's dedupe
|
self.run_test("Get Banner", self.do_get_banner)
|
||||||
# function may bite you.
|
|
||||||
self.progress("Getting banner")
|
|
||||||
if not self.do_get_banner():
|
|
||||||
self.progress("FAILED: get banner")
|
|
||||||
failed = True
|
|
||||||
|
|
||||||
self.progress("Getting autopilot capabilities")
|
self.run_test("Get Capabilities",
|
||||||
if not self.do_get_autopilot_capabilities():
|
self.do_get_autopilot_capabilities)
|
||||||
self.progress("FAILED: get capabilities")
|
|
||||||
failed = True
|
|
||||||
|
|
||||||
self.progress("Setting mode via MAV_COMMAND_DO_SET_MODE")
|
self.run_test("Set mode via MAV_COMMAND_DO_SET_MODE",
|
||||||
if not self.do_set_mode_via_command_long():
|
self.do_set_mode_via_command_long)
|
||||||
failed = True
|
|
||||||
|
|
||||||
# test ServoRelayEvents:
|
self.run_test("Test ServoRelayEvents",
|
||||||
self.progress("########## Test ServoRelayEvents ##########")
|
self.test_servorelayevents)
|
||||||
if not self.test_servorelayevents():
|
|
||||||
self.progress("Failed servo relay events")
|
|
||||||
failed = True
|
|
||||||
|
|
||||||
# Throttle Failsafe
|
self.run_test("Download logs", lambda:
|
||||||
self.progress("#")
|
self.log_download(self.buildlogs_path("APMrover2-log.bin")))
|
||||||
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
|
|
||||||
# if not drive_left_circuit(self):
|
# if not drive_left_circuit(self):
|
||||||
# self.progress("Failed left circuit")
|
# self.progress("Failed left circuit")
|
||||||
# failed = True
|
# failed = True
|
||||||
@ -581,11 +519,11 @@ class AutoTestRover(AutoTest):
|
|||||||
|
|
||||||
except pexpect.TIMEOUT as e:
|
except pexpect.TIMEOUT as e:
|
||||||
self.progress("Failed with timeout")
|
self.progress("Failed with timeout")
|
||||||
failed = True
|
self.fail_list.append( ("*timeout*", None) )
|
||||||
|
|
||||||
self.close()
|
self.close()
|
||||||
|
|
||||||
if failed:
|
if len(self.fail_list):
|
||||||
self.progress("FAILED: %s" % e)
|
self.progress("FAILED STEPS: %s" % self.fail_list)
|
||||||
return False
|
return False
|
||||||
return True
|
return True
|
||||||
|
File diff suppressed because it is too large
Load Diff
@ -11,6 +11,7 @@ from pymavlink import mavutil
|
|||||||
from pysim import util
|
from pysim import util
|
||||||
|
|
||||||
from common import AutoTest
|
from common import AutoTest
|
||||||
|
from common import NotAchievedException
|
||||||
|
|
||||||
# get location of scripts
|
# get location of scripts
|
||||||
testdir = os.path.dirname(os.path.realpath(__file__))
|
testdir = os.path.dirname(os.path.realpath(__file__))
|
||||||
@ -104,7 +105,6 @@ class AutoTestPlane(AutoTest):
|
|||||||
|
|
||||||
def takeoff(self):
|
def takeoff(self):
|
||||||
"""Takeoff get to 30m altitude."""
|
"""Takeoff get to 30m altitude."""
|
||||||
|
|
||||||
self.wait_ready_to_arm()
|
self.wait_ready_to_arm()
|
||||||
self.arm_vehicle()
|
self.arm_vehicle()
|
||||||
|
|
||||||
@ -131,24 +131,21 @@ class AutoTestPlane(AutoTest):
|
|||||||
self.set_rc(3, 2000)
|
self.set_rc(3, 2000)
|
||||||
|
|
||||||
# gain a bit of altitude
|
# 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,
|
self.homeloc.alt+180,
|
||||||
timeout=30):
|
timeout=30)
|
||||||
return False
|
|
||||||
|
|
||||||
# level off
|
# level off
|
||||||
self.set_rc(2, 1500)
|
self.set_rc(2, 1500)
|
||||||
|
|
||||||
self.progress("TAKEOFF COMPLETE")
|
self.progress("TAKEOFF COMPLETE")
|
||||||
return True
|
|
||||||
|
|
||||||
def fly_left_circuit(self):
|
def fly_left_circuit(self):
|
||||||
"""Fly a left circuit, 200m on a side."""
|
"""Fly a left circuit, 200m on a side."""
|
||||||
self.mavproxy.send('switch 4\n')
|
self.mavproxy.send('switch 4\n')
|
||||||
self.wait_mode('FBWA')
|
self.wait_mode('FBWA')
|
||||||
self.set_rc(3, 2000)
|
self.set_rc(3, 2000)
|
||||||
if not self.wait_level_flight():
|
self.wait_level_flight()
|
||||||
return False
|
|
||||||
|
|
||||||
self.progress("Flying left circuit")
|
self.progress("Flying left circuit")
|
||||||
# do 4 turns
|
# do 4 turns
|
||||||
@ -156,28 +153,23 @@ class AutoTestPlane(AutoTest):
|
|||||||
# hard left
|
# hard left
|
||||||
self.progress("Starting turn %u" % i)
|
self.progress("Starting turn %u" % i)
|
||||||
self.set_rc(1, 1000)
|
self.set_rc(1, 1000)
|
||||||
if not self.wait_heading(270 - (90*i), accuracy=10):
|
self.wait_heading(270 - (90*i), accuracy=10)
|
||||||
return False
|
|
||||||
self.set_rc(1, 1500)
|
self.set_rc(1, 1500)
|
||||||
self.progress("Starting leg %u" % i)
|
self.progress("Starting leg %u" % i)
|
||||||
if not self.wait_distance(100, accuracy=20):
|
self.wait_distance(100, accuracy=20)
|
||||||
return False
|
|
||||||
self.progress("Circuit complete")
|
self.progress("Circuit complete")
|
||||||
return True
|
|
||||||
|
|
||||||
def fly_RTL(self):
|
def fly_RTL(self):
|
||||||
"""Fly to home."""
|
"""Fly to home."""
|
||||||
self.progress("Flying home in RTL")
|
self.progress("Flying home in RTL")
|
||||||
self.mavproxy.send('switch 2\n')
|
self.mavproxy.send('switch 2\n')
|
||||||
self.wait_mode('RTL')
|
self.wait_mode('RTL')
|
||||||
if not self.wait_location(self.homeloc,
|
self.wait_location(self.homeloc,
|
||||||
accuracy=120,
|
accuracy=120,
|
||||||
target_altitude=self.homeloc.alt+100,
|
target_altitude=self.homeloc.alt+100,
|
||||||
height_accuracy=20,
|
height_accuracy=20,
|
||||||
timeout=180):
|
timeout=180)
|
||||||
return False
|
|
||||||
self.progress("RTL Complete")
|
self.progress("RTL Complete")
|
||||||
return True
|
|
||||||
|
|
||||||
def fly_LOITER(self, num_circles=4):
|
def fly_LOITER(self, num_circles=4):
|
||||||
"""Loiter where we are."""
|
"""Loiter where we are."""
|
||||||
@ -190,10 +182,8 @@ class AutoTestPlane(AutoTest):
|
|||||||
self.progress("Initial altitude %u\n" % initial_alt)
|
self.progress("Initial altitude %u\n" % initial_alt)
|
||||||
|
|
||||||
while num_circles > 0:
|
while num_circles > 0:
|
||||||
if not self.wait_heading(0, accuracy=10, timeout=60):
|
self.wait_heading(0, accuracy=10, timeout=60)
|
||||||
return False
|
self.wait_heading(180, accuracy=10, timeout=60)
|
||||||
if not self.wait_heading(180, accuracy=10, timeout=60):
|
|
||||||
return False
|
|
||||||
num_circles -= 1
|
num_circles -= 1
|
||||||
self.progress("Loiter %u circles left" % num_circles)
|
self.progress("Loiter %u circles left" % num_circles)
|
||||||
|
|
||||||
@ -207,10 +197,9 @@ class AutoTestPlane(AutoTest):
|
|||||||
|
|
||||||
if abs(final_alt - initial_alt) > 20:
|
if abs(final_alt - initial_alt) > 20:
|
||||||
self.progress("Failed to maintain altitude")
|
self.progress("Failed to maintain altitude")
|
||||||
return False
|
raise NotAchievedException()
|
||||||
|
|
||||||
self.progress("Completed Loiter OK")
|
self.progress("Completed Loiter OK")
|
||||||
return True
|
|
||||||
|
|
||||||
def fly_CIRCLE(self, num_circles=1):
|
def fly_CIRCLE(self, num_circles=1):
|
||||||
"""Circle where we are."""
|
"""Circle where we are."""
|
||||||
@ -223,10 +212,8 @@ class AutoTestPlane(AutoTest):
|
|||||||
self.progress("Initial altitude %u\n" % initial_alt)
|
self.progress("Initial altitude %u\n" % initial_alt)
|
||||||
|
|
||||||
while num_circles > 0:
|
while num_circles > 0:
|
||||||
if not self.wait_heading(0, accuracy=10, timeout=60):
|
self.wait_heading(0, accuracy=10, timeout=60)
|
||||||
return False
|
self.wait_heading(180, accuracy=10, timeout=60)
|
||||||
if not self.wait_heading(180, accuracy=10, timeout=60):
|
|
||||||
return False
|
|
||||||
num_circles -= 1
|
num_circles -= 1
|
||||||
self.progress("CIRCLE %u circles left" % num_circles)
|
self.progress("CIRCLE %u circles left" % num_circles)
|
||||||
|
|
||||||
@ -240,10 +227,9 @@ class AutoTestPlane(AutoTest):
|
|||||||
|
|
||||||
if abs(final_alt - initial_alt) > 20:
|
if abs(final_alt - initial_alt) > 20:
|
||||||
self.progress("Failed to maintain altitude")
|
self.progress("Failed to maintain altitude")
|
||||||
return False
|
raise NotAchievedException()
|
||||||
|
|
||||||
self.progress("Completed CIRCLE OK")
|
self.progress("Completed CIRCLE OK")
|
||||||
return True
|
|
||||||
|
|
||||||
def wait_level_flight(self, accuracy=5, timeout=30):
|
def wait_level_flight(self, accuracy=5, timeout=30):
|
||||||
"""Wait for level flight."""
|
"""Wait for level flight."""
|
||||||
@ -259,9 +245,9 @@ class AutoTestPlane(AutoTest):
|
|||||||
self.progress("Roll=%.1f Pitch=%.1f" % (roll, pitch))
|
self.progress("Roll=%.1f Pitch=%.1f" % (roll, pitch))
|
||||||
if math.fabs(roll) <= accuracy and math.fabs(pitch) <= accuracy:
|
if math.fabs(roll) <= accuracy and math.fabs(pitch) <= accuracy:
|
||||||
self.progress("Attained level flight")
|
self.progress("Attained level flight")
|
||||||
return True
|
return
|
||||||
self.progress("Failed to attain level flight")
|
self.progress("Failed to attain level flight")
|
||||||
return False
|
raise NotAchievedException()
|
||||||
|
|
||||||
def change_altitude(self, altitude, accuracy=30):
|
def change_altitude(self, altitude, accuracy=30):
|
||||||
"""Get to a given altitude."""
|
"""Get to a given altitude."""
|
||||||
@ -272,8 +258,7 @@ class AutoTestPlane(AutoTest):
|
|||||||
self.set_rc(2, 2000)
|
self.set_rc(2, 2000)
|
||||||
else:
|
else:
|
||||||
self.set_rc(2, 1000)
|
self.set_rc(2, 1000)
|
||||||
if not self.wait_altitude(altitude-accuracy/2, altitude+accuracy/2):
|
self.wait_altitude(altitude-accuracy/2, altitude+accuracy/2)
|
||||||
return False
|
|
||||||
self.set_rc(2, 1500)
|
self.set_rc(2, 1500)
|
||||||
self.progress("Reached target altitude at %u" %
|
self.progress("Reached target altitude at %u" %
|
||||||
self.mav.messages['VFR_HUD'].alt)
|
self.mav.messages['VFR_HUD'].alt)
|
||||||
@ -283,8 +268,7 @@ class AutoTestPlane(AutoTest):
|
|||||||
"""Fly a left axial roll."""
|
"""Fly a left axial roll."""
|
||||||
# full throttle!
|
# full throttle!
|
||||||
self.set_rc(3, 2000)
|
self.set_rc(3, 2000)
|
||||||
if not self.change_altitude(self.homeloc.alt+300):
|
self.change_altitude(self.homeloc.alt+300)
|
||||||
return False
|
|
||||||
|
|
||||||
# fly the roll in manual
|
# fly the roll in manual
|
||||||
self.mavproxy.send('switch 6\n')
|
self.mavproxy.send('switch 6\n')
|
||||||
@ -293,15 +277,13 @@ class AutoTestPlane(AutoTest):
|
|||||||
while count > 0:
|
while count > 0:
|
||||||
self.progress("Starting roll")
|
self.progress("Starting roll")
|
||||||
self.set_rc(1, 1000)
|
self.set_rc(1, 1000)
|
||||||
if not self.wait_roll(-150, accuracy=90):
|
try:
|
||||||
self.set_rc(1, 1500)
|
self.wait_roll(-150, accuracy=90)
|
||||||
return False
|
self.wait_roll(150, accuracy=90)
|
||||||
if not self.wait_roll(150, accuracy=90):
|
self.wait_roll(0, accuracy=90)
|
||||||
self.set_rc(1, 1500)
|
except Exception as e:
|
||||||
return False
|
self.set_rc(1,1500)
|
||||||
if not self.wait_roll(0, accuracy=90):
|
raise e
|
||||||
self.set_rc(1, 1500)
|
|
||||||
return False
|
|
||||||
count -= 1
|
count -= 1
|
||||||
|
|
||||||
# back to FBWA
|
# back to FBWA
|
||||||
@ -315,9 +297,7 @@ class AutoTestPlane(AutoTest):
|
|||||||
"""Fly a inside loop."""
|
"""Fly a inside loop."""
|
||||||
# full throttle!
|
# full throttle!
|
||||||
self.set_rc(3, 2000)
|
self.set_rc(3, 2000)
|
||||||
if not self.change_altitude(self.homeloc.alt+300):
|
self.change_altitude(self.homeloc.alt+300)
|
||||||
return False
|
|
||||||
|
|
||||||
# fly the loop in manual
|
# fly the loop in manual
|
||||||
self.mavproxy.send('switch 6\n')
|
self.mavproxy.send('switch 6\n')
|
||||||
self.wait_mode('MANUAL')
|
self.wait_mode('MANUAL')
|
||||||
@ -325,10 +305,8 @@ class AutoTestPlane(AutoTest):
|
|||||||
while count > 0:
|
while count > 0:
|
||||||
self.progress("Starting loop")
|
self.progress("Starting loop")
|
||||||
self.set_rc(2, 1000)
|
self.set_rc(2, 1000)
|
||||||
if not self.wait_pitch(-60, accuracy=20):
|
self.wait_pitch(-60, accuracy=20)
|
||||||
return False
|
self.wait_pitch(0, accuracy=20)
|
||||||
if not self.wait_pitch(0, accuracy=20):
|
|
||||||
return False
|
|
||||||
count -= 1
|
count -= 1
|
||||||
|
|
||||||
# back to FBWA
|
# back to FBWA
|
||||||
@ -343,8 +321,7 @@ class AutoTestPlane(AutoTest):
|
|||||||
# full throttle!
|
# full throttle!
|
||||||
self.set_rc(3, 2000)
|
self.set_rc(3, 2000)
|
||||||
self.set_rc(2, 1300)
|
self.set_rc(2, 1300)
|
||||||
if not self.change_altitude(self.homeloc.alt+300):
|
self.change_altitude(self.homeloc.alt+300)
|
||||||
return False
|
|
||||||
self.set_rc(2, 1500)
|
self.set_rc(2, 1500)
|
||||||
|
|
||||||
self.mavproxy.send("mode STABILIZE\n")
|
self.mavproxy.send("mode STABILIZE\n")
|
||||||
@ -354,17 +331,13 @@ class AutoTestPlane(AutoTest):
|
|||||||
while count > 0:
|
while count > 0:
|
||||||
self.progress("Starting roll")
|
self.progress("Starting roll")
|
||||||
self.set_rc(1, 2000)
|
self.set_rc(1, 2000)
|
||||||
if not self.wait_roll(-150, accuracy=90):
|
self.wait_roll(-150, accuracy=90)
|
||||||
return False
|
self.wait_roll(150, accuracy=90)
|
||||||
if not self.wait_roll(150, accuracy=90):
|
self.wait_roll(0, accuracy=90)
|
||||||
return False
|
|
||||||
if not self.wait_roll(0, accuracy=90):
|
|
||||||
return False
|
|
||||||
count -= 1
|
count -= 1
|
||||||
|
|
||||||
self.set_rc(1, 1500)
|
self.set_rc(1, 1500)
|
||||||
if not self.wait_roll(0, accuracy=5):
|
self.wait_roll(0, accuracy=5)
|
||||||
return False
|
|
||||||
|
|
||||||
# back to FBWA
|
# back to FBWA
|
||||||
self.mavproxy.send('mode FBWA\n')
|
self.mavproxy.send('mode FBWA\n')
|
||||||
@ -377,8 +350,7 @@ class AutoTestPlane(AutoTest):
|
|||||||
# full throttle!
|
# full throttle!
|
||||||
self.set_rc(3, 2000)
|
self.set_rc(3, 2000)
|
||||||
self.set_rc(2, 1300)
|
self.set_rc(2, 1300)
|
||||||
if not self.change_altitude(self.homeloc.alt+300):
|
self.change_altitude(self.homeloc.alt+300)
|
||||||
return False
|
|
||||||
self.set_rc(2, 1500)
|
self.set_rc(2, 1500)
|
||||||
|
|
||||||
self.mavproxy.send("mode ACRO\n")
|
self.mavproxy.send("mode ACRO\n")
|
||||||
@ -388,12 +360,9 @@ class AutoTestPlane(AutoTest):
|
|||||||
while count > 0:
|
while count > 0:
|
||||||
self.progress("Starting roll")
|
self.progress("Starting roll")
|
||||||
self.set_rc(1, 1000)
|
self.set_rc(1, 1000)
|
||||||
if not self.wait_roll(-150, accuracy=90):
|
self.wait_roll(-150, accuracy=90)
|
||||||
return False
|
self.wait_roll(150, accuracy=90)
|
||||||
if not self.wait_roll(150, accuracy=90):
|
self.wait_roll(0, accuracy=90)
|
||||||
return False
|
|
||||||
if not self.wait_roll(0, accuracy=90):
|
|
||||||
return False
|
|
||||||
count -= 1
|
count -= 1
|
||||||
self.set_rc(1, 1500)
|
self.set_rc(1, 1500)
|
||||||
|
|
||||||
@ -410,10 +379,8 @@ class AutoTestPlane(AutoTest):
|
|||||||
while count > 0:
|
while count > 0:
|
||||||
self.progress("Starting loop")
|
self.progress("Starting loop")
|
||||||
self.set_rc(2, 1000)
|
self.set_rc(2, 1000)
|
||||||
if not self.wait_pitch(-60, accuracy=20):
|
self.wait_pitch(-60, accuracy=20)
|
||||||
return False
|
self.wait_pitch(0, accuracy=20)
|
||||||
if not self.wait_pitch(0, accuracy=20):
|
|
||||||
return False
|
|
||||||
count -= 1
|
count -= 1
|
||||||
|
|
||||||
self.set_rc(2, 1500)
|
self.set_rc(2, 1500)
|
||||||
@ -447,13 +414,14 @@ class AutoTestPlane(AutoTest):
|
|||||||
# hard left
|
# hard left
|
||||||
self.progress("Starting turn %u" % i)
|
self.progress("Starting turn %u" % i)
|
||||||
self.set_rc(1, 1800)
|
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)
|
self.set_rc(1, 1500)
|
||||||
return False
|
raise e
|
||||||
self.set_rc(1, 1500)
|
self.set_rc(1, 1500)
|
||||||
self.progress("Starting leg %u" % i)
|
self.progress("Starting leg %u" % i)
|
||||||
if not self.wait_distance(100, accuracy=20):
|
self.wait_distance(100, accuracy=20)
|
||||||
return False
|
|
||||||
self.progress("Circuit complete")
|
self.progress("Circuit complete")
|
||||||
|
|
||||||
self.progress("Flying rudder left circuit")
|
self.progress("Flying rudder left circuit")
|
||||||
@ -462,13 +430,14 @@ class AutoTestPlane(AutoTest):
|
|||||||
# hard left
|
# hard left
|
||||||
self.progress("Starting turn %u" % i)
|
self.progress("Starting turn %u" % i)
|
||||||
self.set_rc(4, 1900)
|
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)
|
self.set_rc(4, 1500)
|
||||||
return False
|
raise e
|
||||||
self.set_rc(4, 1500)
|
self.set_rc(4, 1500)
|
||||||
self.progress("Starting leg %u" % i)
|
self.progress("Starting leg %u" % i)
|
||||||
if not self.wait_distance(100, accuracy=20):
|
self.wait_distance(100, accuracy=20)
|
||||||
return False
|
|
||||||
self.progress("Circuit complete")
|
self.progress("Circuit complete")
|
||||||
|
|
||||||
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
||||||
@ -482,7 +451,7 @@ class AutoTestPlane(AutoTest):
|
|||||||
|
|
||||||
if abs(final_alt - initial_alt) > 20:
|
if abs(final_alt - initial_alt) > 20:
|
||||||
self.progress("Failed to maintain altitude")
|
self.progress("Failed to maintain altitude")
|
||||||
return False
|
raise NotAchievedException()
|
||||||
|
|
||||||
return self.wait_level_flight()
|
return self.wait_level_flight()
|
||||||
|
|
||||||
@ -495,22 +464,17 @@ class AutoTestPlane(AutoTest):
|
|||||||
self.mavproxy.expect('Requesting [0-9]+ waypoints')
|
self.mavproxy.expect('Requesting [0-9]+ waypoints')
|
||||||
self.mavproxy.send('switch 1\n') # auto mode
|
self.mavproxy.send('switch 1\n') # auto mode
|
||||||
self.wait_mode('AUTO')
|
self.wait_mode('AUTO')
|
||||||
if not self.wait_waypoint(1, 7, max_dist=60):
|
self.wait_waypoint(1, 7, max_dist=60)
|
||||||
return False
|
self.wait_groundspeed(0, 0.5, timeout=60)
|
||||||
if not self.wait_groundspeed(0, 0.5, timeout=60):
|
|
||||||
return False
|
|
||||||
self.mavproxy.expect("Auto disarmed")
|
self.mavproxy.expect("Auto disarmed")
|
||||||
self.progress("Mission OK")
|
self.progress("Mission OK")
|
||||||
return True
|
|
||||||
|
|
||||||
def autotest(self):
|
def autotest(self):
|
||||||
"""Autotest ArduPlane in SITL."""
|
"""Autotest ArduPlane in SITL."""
|
||||||
if not self.hasInit:
|
if not self.hasInit:
|
||||||
self.init()
|
self.init()
|
||||||
|
|
||||||
failed = False
|
self.fail_list = []
|
||||||
fail_list = []
|
|
||||||
e = 'None'
|
|
||||||
try:
|
try:
|
||||||
self.progress("Waiting for a heartbeat with mavlink protocol %s"
|
self.progress("Waiting for a heartbeat with mavlink protocol %s"
|
||||||
% self.mav.WIRE_PROTOCOL_VERSION)
|
% self.mav.WIRE_PROTOCOL_VERSION)
|
||||||
@ -526,69 +490,42 @@ class AutoTestPlane(AutoTest):
|
|||||||
self.mav.wait_gps_fix()
|
self.mav.wait_gps_fix()
|
||||||
self.homeloc = self.mav.location()
|
self.homeloc = self.mav.location()
|
||||||
self.progress("Home location: %s" % self.homeloc)
|
self.progress("Home location: %s" % self.homeloc)
|
||||||
if not self.takeoff():
|
|
||||||
self.progress("Failed takeoff")
|
self.run_test("Takeoff", self.takeoff)
|
||||||
failed = True
|
|
||||||
fail_list.append("takeoff")
|
self.run_test("Fly left circuit", self.fly_left_circuit)
|
||||||
if not self.fly_left_circuit():
|
|
||||||
self.progress("Failed left circuit")
|
self.run_test("Left roll", lambda: self.axial_left_roll(1))
|
||||||
failed = True
|
|
||||||
fail_list.append("left_circuit")
|
self.run_test("Inside loop", self.inside_loop)
|
||||||
if not self.axial_left_roll(1):
|
|
||||||
self.progress("Failed left roll")
|
self.run_test("Stablize test", self.test_stabilize)
|
||||||
failed = True
|
|
||||||
fail_list.append("left_roll")
|
self.run_test("ACRO test", self.test_acro)
|
||||||
if not self.inside_loop():
|
|
||||||
self.progress("Failed inside loop")
|
self.run_test("FBWB test", self.test_FBWB)
|
||||||
failed = True
|
|
||||||
fail_list.append("inside_loop")
|
self.run_test("CRUISE test", lambda: self.test_FBWB(mode='CRUISE'))
|
||||||
if not self.test_stabilize():
|
|
||||||
self.progress("Failed stabilize test")
|
self.run_test("RTL test", self.fly_RTL)
|
||||||
failed = True
|
|
||||||
fail_list.append("stabilize")
|
self.run_test("LOITER test", self.fly_LOITER)
|
||||||
if not self.test_acro():
|
|
||||||
self.progress("Failed ACRO test")
|
self.run_test("CIRCLE test", self.fly_CIRCLE)
|
||||||
failed = True
|
|
||||||
fail_list.append("acro")
|
self.run_test("Mission test", lambda: self.fly_mission(os.path.join(testdir, "ap1.txt"),
|
||||||
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"),
|
|
||||||
height_accuracy=10,
|
height_accuracy=10,
|
||||||
target_altitude=self.homeloc.alt+100):
|
target_altitude=self.homeloc.alt+100))
|
||||||
self.progress("Failed mission")
|
|
||||||
failed = True
|
self.run_test("Log download", lambda: self.log_download(self.buildlogs_path("ArduPlane-log.bin")))
|
||||||
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")
|
|
||||||
except pexpect.TIMEOUT as e:
|
except pexpect.TIMEOUT as e:
|
||||||
self.progress("Failed with timeout")
|
self.progress("Failed with timeout")
|
||||||
failed = True
|
self.fail_list.append("timeout")
|
||||||
fail_list.append("timeout")
|
|
||||||
|
|
||||||
self.close()
|
self.close()
|
||||||
|
|
||||||
if failed:
|
if len(self.fail_list):
|
||||||
self.progress("FAILED: %s" % e)
|
self.progress("FAILED: %s" % self.fail_list)
|
||||||
self.progress("Fail list: %s" % fail_list)
|
|
||||||
return False
|
return False
|
||||||
return True
|
return True
|
||||||
|
@ -103,39 +103,27 @@ class AutoTestSub(AutoTest):
|
|||||||
self.set_rc(5, 1600)
|
self.set_rc(5, 1600)
|
||||||
self.set_rc(6, 1550)
|
self.set_rc(6, 1550)
|
||||||
|
|
||||||
if not self.wait_distance(50, accuracy=7, timeout=200):
|
self.wait_distance(50, accuracy=7, timeout=200)
|
||||||
return False
|
|
||||||
|
|
||||||
self.set_rc(4, 1550)
|
self.set_rc(4, 1550)
|
||||||
|
|
||||||
if not self.wait_heading(0):
|
self.wait_heading(0)
|
||||||
return False
|
|
||||||
|
|
||||||
self.set_rc(4, 1500)
|
self.set_rc(4, 1500)
|
||||||
|
|
||||||
if not self.wait_distance(50, accuracy=7, timeout=100):
|
self.wait_distance(50, accuracy=7, timeout=100)
|
||||||
return False
|
|
||||||
|
|
||||||
self.set_rc(4, 1550)
|
self.set_rc(4, 1550)
|
||||||
|
|
||||||
if not self.wait_heading(0):
|
self.wait_heading(0)
|
||||||
return False
|
|
||||||
|
|
||||||
self.set_rc(4, 1500)
|
self.set_rc(4, 1500)
|
||||||
self.set_rc(5, 1500)
|
self.set_rc(5, 1500)
|
||||||
self.set_rc(6, 1100)
|
self.set_rc(6, 1100)
|
||||||
|
|
||||||
if not self.wait_distance(75, accuracy=7, timeout=100):
|
self.wait_distance(75, accuracy=7, timeout=100)
|
||||||
return False
|
|
||||||
|
|
||||||
self.set_rc_default()
|
self.set_rc_default()
|
||||||
|
|
||||||
self.disarm_vehicle()
|
self.disarm_vehicle()
|
||||||
self.progress("Manual dive OK")
|
self.progress("Manual dive OK")
|
||||||
return True
|
|
||||||
|
|
||||||
def dive_mission(self, filename):
|
def dive_mission(self, filename):
|
||||||
|
|
||||||
self.progress("Executing mission %s" % filename)
|
self.progress("Executing mission %s" % filename)
|
||||||
self.mavproxy.send('wp load %s\n' % filename)
|
self.mavproxy.send('wp load %s\n' % filename)
|
||||||
self.mavproxy.expect('Flight plan received')
|
self.mavproxy.expect('Flight plan received')
|
||||||
@ -143,28 +131,23 @@ class AutoTestSub(AutoTest):
|
|||||||
self.mavproxy.expect('Saved [0-9]+ waypoints')
|
self.mavproxy.expect('Saved [0-9]+ waypoints')
|
||||||
self.set_rc_default()
|
self.set_rc_default()
|
||||||
|
|
||||||
if not self.arm_vehicle():
|
self.arm_vehicle()
|
||||||
self.progress("Failed to ARM")
|
|
||||||
return False
|
|
||||||
|
|
||||||
self.mavproxy.send('mode auto\n')
|
self.mavproxy.send('mode auto\n')
|
||||||
self.wait_mode('AUTO')
|
self.wait_mode('AUTO')
|
||||||
|
|
||||||
if not self.wait_waypoint(1, 5, max_dist=5):
|
self.wait_waypoint(1, 5, max_dist=5)
|
||||||
return False
|
|
||||||
|
|
||||||
self.disarm_vehicle()
|
self.disarm_vehicle()
|
||||||
|
|
||||||
self.progress("Mission OK")
|
self.progress("Mission OK")
|
||||||
return True
|
|
||||||
|
|
||||||
def autotest(self):
|
def autotest(self):
|
||||||
"""Autotest ArduSub in SITL."""
|
"""Autotest ArduSub in SITL."""
|
||||||
if not self.hasInit:
|
if not self.hasInit:
|
||||||
self.init()
|
self.init()
|
||||||
|
|
||||||
failed = False
|
self.fail_list = []
|
||||||
e = 'None'
|
|
||||||
try:
|
try:
|
||||||
self.progress("Waiting for a heartbeat with mavlink protocol %s"
|
self.progress("Waiting for a heartbeat with mavlink protocol %s"
|
||||||
% self.mav.WIRE_PROTOCOL_VERSION)
|
% self.mav.WIRE_PROTOCOL_VERSION)
|
||||||
@ -179,25 +162,22 @@ class AutoTestSub(AutoTest):
|
|||||||
self.homeloc = self.mav.location()
|
self.homeloc = self.mav.location()
|
||||||
self.progress("Home location: %s" % self.homeloc)
|
self.progress("Home location: %s" % self.homeloc)
|
||||||
self.set_rc_default()
|
self.set_rc_default()
|
||||||
if not self.arm_vehicle():
|
|
||||||
self.progress("Failed to ARM")
|
self.run_test("Arm vehicle", self.arm_vehicle)
|
||||||
failed = True
|
|
||||||
if not self.dive_manual():
|
self.run_test("Dive manual", self.dive_manual)
|
||||||
self.progress("Failed manual dive")
|
|
||||||
failed = True
|
self.run_test("Dive mission", lambda: self.dive_mission(os.path.join(testdir, "sub_mission.txt")))
|
||||||
if not self.dive_mission(os.path.join(testdir, "sub_mission.txt")):
|
|
||||||
self.progress("Failed auto mission")
|
self.run_test("Log download", lambda: self.log_download(self.buildlogs_path("ArduSub-log.bin")))
|
||||||
failed = True
|
|
||||||
if not self.log_download(self.buildlogs_path("ArduSub-log.bin")):
|
|
||||||
self.progress("Failed log download")
|
|
||||||
failed = True
|
|
||||||
except pexpect.TIMEOUT as e:
|
except pexpect.TIMEOUT as e:
|
||||||
self.progress("Failed with timeout")
|
self.progress("Failed with timeout")
|
||||||
failed = True
|
self.fail_list.append("Failed with timeout")
|
||||||
|
|
||||||
self.close()
|
self.close()
|
||||||
|
|
||||||
if failed:
|
if len(self.fail_list):
|
||||||
self.progress("FAILED: %s" % e)
|
self.progress("FAILED: %s" % self.fail_list)
|
||||||
return False
|
return False
|
||||||
return True
|
return True
|
||||||
|
@ -134,25 +134,24 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
self.mavproxy.expect('Requesting [0-9]+ waypoints')
|
self.mavproxy.expect('Requesting [0-9]+ waypoints')
|
||||||
self.mavproxy.send('mode AUTO\n')
|
self.mavproxy.send('mode AUTO\n')
|
||||||
self.wait_mode('AUTO')
|
self.wait_mode('AUTO')
|
||||||
if not self.wait_waypoint(1, 19, max_dist=60, timeout=1200):
|
self.wait_waypoint(1, 19, max_dist=60, timeout=1200)
|
||||||
return False
|
|
||||||
self.mavproxy.expect('DISARMED')
|
self.mavproxy.expect('DISARMED')
|
||||||
# wait for blood sample here
|
# wait for blood sample here
|
||||||
self.mavproxy.send('wp set 20\n')
|
self.mavproxy.send('wp set 20\n')
|
||||||
self.arm_vehicle()
|
self.arm_vehicle()
|
||||||
if not self.wait_waypoint(20, 34, max_dist=60, timeout=1200):
|
self.wait_waypoint(20, 34, max_dist=60, timeout=1200)
|
||||||
return False
|
|
||||||
self.mavproxy.expect('DISARMED')
|
self.mavproxy.expect('DISARMED')
|
||||||
self.progress("Mission OK")
|
self.progress("Mission OK")
|
||||||
return True
|
|
||||||
|
|
||||||
def autotest(self):
|
def autotest(self):
|
||||||
"""Autotest QuadPlane in SITL."""
|
"""Autotest QuadPlane in SITL."""
|
||||||
if not self.hasInit:
|
if not self.hasInit:
|
||||||
self.init()
|
self.init()
|
||||||
|
|
||||||
failed = False
|
self.fail_list = []
|
||||||
e = 'None'
|
|
||||||
try:
|
try:
|
||||||
self.progress("Waiting for a heartbeat with mavlink protocol %s"
|
self.progress("Waiting for a heartbeat with mavlink protocol %s"
|
||||||
% self.mav.WIRE_PROTOCOL_VERSION)
|
% self.mav.WIRE_PROTOCOL_VERSION)
|
||||||
@ -174,16 +173,15 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
m = os.path.join(testdir, "ArduPlane-Missions/Dalby-OBC2016.txt")
|
m = os.path.join(testdir, "ArduPlane-Missions/Dalby-OBC2016.txt")
|
||||||
f = os.path.join(testdir,
|
f = os.path.join(testdir,
|
||||||
"ArduPlane-Missions/Dalby-OBC2016-fence.txt")
|
"ArduPlane-Missions/Dalby-OBC2016-fence.txt")
|
||||||
if not self.fly_mission(m, f):
|
|
||||||
self.progress("Failed mission")
|
self.run_test("Mission", lambda: self.fly_mission(m, f))
|
||||||
failed = True
|
|
||||||
except pexpect.TIMEOUT as e:
|
except pexpect.TIMEOUT as e:
|
||||||
self.progress("Failed with timeout")
|
self.progress("Failed with timeout")
|
||||||
failed = True
|
self.fail_list.append("Failed with timeout")
|
||||||
|
|
||||||
self.close()
|
self.close()
|
||||||
|
|
||||||
if failed:
|
if len(self.fail_list):
|
||||||
self.progress("FAILED: %s" % e)
|
self.progress("FAILED: %s" % self.fail_list)
|
||||||
return False
|
return False
|
||||||
return True
|
return True
|
||||||
|
Loading…
Reference in New Issue
Block a user