mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
Tools: remove hard-coded FRAME global, specify same via parameter
This commit is contained in:
parent
2c0b687b9d
commit
068c310ed5
@ -21,7 +21,6 @@ from pysim import util
|
|||||||
# get location of scripts
|
# get location of scripts
|
||||||
testdir = os.path.dirname(os.path.realpath(__file__))
|
testdir = os.path.dirname(os.path.realpath(__file__))
|
||||||
|
|
||||||
FRAME = '+'
|
|
||||||
HOME = mavutil.location(-35.362938, 149.165085, 584, 270)
|
HOME = mavutil.location(-35.362938, 149.165085, 584, 270)
|
||||||
AVCHOME = mavutil.location(40.072842, -105.230575, 1586, 0)
|
AVCHOME = mavutil.location(40.072842, -105.230575, 1586, 0)
|
||||||
|
|
||||||
@ -954,7 +953,7 @@ def setup_rc(mavproxy):
|
|||||||
mavproxy.send('rc 3 1000\n')
|
mavproxy.send('rc 3 1000\n')
|
||||||
|
|
||||||
|
|
||||||
def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=False):
|
def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame='+', params_file=None):
|
||||||
"""Fly ArduCopter in SITL.
|
"""Fly ArduCopter in SITL.
|
||||||
|
|
||||||
you can pass viewerip as an IP address to optionally send fg and
|
you can pass viewerip as an IP address to optionally send fg and
|
||||||
@ -963,12 +962,14 @@ def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fal
|
|||||||
global homeloc
|
global homeloc
|
||||||
|
|
||||||
home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading)
|
home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading)
|
||||||
sitl = util.start_SITL(binary, wipe=True, model='+', home=home, speedup=speedup_default)
|
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')
|
mavproxy = util.start_MAVProxy_SITL('ArduCopter', options='--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter')
|
||||||
mavproxy.expect('Received [0-9]+ parameters')
|
mavproxy.expect('Received [0-9]+ parameters')
|
||||||
|
|
||||||
# setup test parameters
|
# setup test parameters
|
||||||
mavproxy.send("param load %s/default_params/copter.parm\n" % testdir)
|
if params_file is None:
|
||||||
|
params_file = "{testdir}/default_params/copter.parm"
|
||||||
|
mavproxy.send("param load %s\n" % params_file.format(testdir=testdir))
|
||||||
mavproxy.expect('Loaded [0-9]+ parameters')
|
mavproxy.expect('Loaded [0-9]+ parameters')
|
||||||
mavproxy.send("param set LOG_REPLAY 1\n")
|
mavproxy.send("param set LOG_REPLAY 1\n")
|
||||||
mavproxy.send("param set LOG_DISARMED 1\n")
|
mavproxy.send("param set LOG_DISARMED 1\n")
|
||||||
@ -978,7 +979,7 @@ def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fal
|
|||||||
util.pexpect_close(mavproxy)
|
util.pexpect_close(mavproxy)
|
||||||
util.pexpect_close(sitl)
|
util.pexpect_close(sitl)
|
||||||
|
|
||||||
sitl = util.start_SITL(binary, model='+', home=home, speedup=speedup_default, valgrind=valgrind, gdb=gdb)
|
sitl = util.start_SITL(binary, model=frame, home=home, speedup=speedup_default, valgrind=valgrind, gdb=gdb)
|
||||||
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=5'
|
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=5'
|
||||||
if viewerip:
|
if viewerip:
|
||||||
options += ' --out=%s:14550' % viewerip
|
options += ' --out=%s:14550' % viewerip
|
||||||
|
Loading…
Reference in New Issue
Block a user