Tools: autotest: option to run different frame

This commit is contained in:
Peter Barker 2017-05-24 17:54:44 +10:00 committed by Randy Mackay
parent 96cfba971c
commit 2ddf7f99b5
2 changed files with 14 additions and 4 deletions

View File

@ -17,6 +17,9 @@ from pymavlink import mavutil, mavwp
from common import *
from pysim import util
from pysim import vehicleinfo
vinfo = vehicleinfo.VehicleInfo()
# get location of scripts
testdir = os.path.dirname(os.path.realpath(__file__))
@ -957,7 +960,7 @@ def setup_rc(mavproxy):
mavproxy.send('rc 3 1000\n')
def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame='+', params_file=None):
def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params_file=None):
"""Fly ArduCopter in SITL.
you can pass viewerip as an IP address to optionally send fg and
@ -965,6 +968,9 @@ def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fal
"""
global homeloc
if frame is None:
frame = '+'
home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading)
sitl = util.start_SITL(binary, wipe=True, model=frame, home=home, speedup=speedup_default)
mavproxy = util.start_MAVProxy_SITL('ArduCopter', options='--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter')
@ -972,8 +978,11 @@ def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fal
# setup test parameters
if params_file is None:
params_file = "{testdir}/default_params/copter.parm"
mavproxy.send("param load %s\n" % params_file.format(testdir=testdir))
params = vinfo.options["ArduCopter"]["frames"][frame]["default_params_filename"]
if not isinstance(params, list):
params = [params]
for x in params:
mavproxy.send("param load %s\n" % os.path.join(testdir, x))
mavproxy.expect('Loaded [0-9]+ parameters')
mavproxy.send("param set LOG_REPLAY 1\n")
mavproxy.send("param set LOG_DISARMED 1\n")

View File

@ -168,6 +168,7 @@ parser.add_option("--valgrind", default=False, action='store_true', help='run Ar
parser.add_option("--gdb", default=False, action='store_true', help='run ArduPilot binaries under gdb')
parser.add_option("--debug", default=False, action='store_true', help='make built binaries debug binaries')
parser.add_option("-j", default=None, type='int', help='build CPUs')
parser.add_option("--frame", type='string', default=None, help='specify frame type')
opts, args = parser.parse_args()
@ -301,7 +302,7 @@ def run_step(step):
return get_default_params('ArduSub', binary)
if step == 'fly.ArduCopter':
return arducopter.fly_ArduCopter(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb)
return arducopter.fly_ArduCopter(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, frame=opts.frame)
if step == 'fly.CopterAVC':
return arducopter.fly_CopterAVC(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb)