diff --git a/Tools/scripts/runcoptertest.py b/Tools/scripts/runcoptertest.py new file mode 100755 index 0000000000..7085d08a89 --- /dev/null +++ b/Tools/scripts/runcoptertest.py @@ -0,0 +1,58 @@ +#!/usr/bin/env python + +import pexpect, time, sys +from pymavlink import mavutil + +def wait_heartbeat(mav, timeout=10): + '''wait for a heartbeat''' + start_time = time.time() + while time.time() < start_time+timeout: + if mav.recv_match(type='HEARTBEAT', blocking=True, timeout=0.5) is not None: + return + raise Exception("Failed to get heartbeat") + +def wait_mode(mav, modes, timeout=10): + '''wait for one of a set of flight modes''' + start_time = time.time() + last_mode = None + while time.time() < start_time+timeout: + wait_heartbeat(mav, timeout=10) + if mav.flightmode != last_mode: + print("Flightmode %s" % mav.flightmode) + last_mode = mav.flightmode + if mav.flightmode in modes: + return + print("Failed to get mode from %s" % modes) + sys.exit(1) + +def wait_time(mav, simtime): + '''wait for simulation time to pass''' + imu = mav.recv_match(type='RAW_IMU', blocking=True) + t1 = imu.time_usec*1.0e-6 + while True: + imu = mav.recv_match(type='RAW_IMU', blocking=True) + t2 = imu.time_usec*1.0e-6 + if t2 - t1 > simtime: + break + +cmd = '../Tools/autotest/sim_vehicle.py -D' +mavproxy = pexpect.spawn(cmd, logfile=sys.stdout, timeout=30) +mavproxy.expect("Frame") + +mav = mavutil.mavlink_connection('127.0.0.1:14550') + +wait_mode(mav, ['STABILIZE']) +mavproxy.send('speedup 40\n') +mavproxy.expect('using GPS') +mavproxy.expect('using GPS') +mavproxy.expect('using GPS') +mavproxy.expect('using GPS') +mavproxy.send('arm throttle\n') +mavproxy.expect('Arming') +mavproxy.send('mode loiter\n') +wait_mode(mav, ['LOITER']) +mavproxy.send('rc 3 2000\n') +wait_time(mav, 20) +mavproxy.send('rc 3 1500\n') +mavproxy.send('mode CIRCLE\n') +wait_time(mav, 90) diff --git a/Tools/scripts/runplanetest.py b/Tools/scripts/runplanetest.py index 9b8263c03b..d94a55a243 100755 --- a/Tools/scripts/runplanetest.py +++ b/Tools/scripts/runplanetest.py @@ -35,21 +35,18 @@ def wait_time(mav, simtime): if t2 - t1 > simtime: break -cmd = 'sim_vehicle.py -j4 -D -f plane' +cmd = '../Tools/autotest/sim_vehicle.py -D -f quadplane' mavproxy = pexpect.spawn(cmd, logfile=sys.stdout, timeout=30) mavproxy.expect("ArduPilot Ready") mav = mavutil.mavlink_connection('127.0.0.1:14550') -wait_mode(mav, ['MANUAL']) -mavproxy.send('wp list\n') -mavproxy.expect('Requesting') -wait_time(mav, 30) -mavproxy.send('arm throttle\n') +mavproxy.send('speedup 40\n') +mavproxy.expect('using GPS') +mavproxy.expect('using GPS') +mavproxy.expect('using GPS') +mavproxy.expect('using GPS') mavproxy.send('auto\n') +mavproxy.send('arm throttle\n') wait_mode(mav, ['AUTO']) -mavproxy.send('module load console\n') -mavproxy.send('module load map\n') -mavproxy.send('map set showsimpos 1\n') -mavproxy.logfile = None -mavproxy.interact() +mavproxy.expect("Mission: 5 WP")