mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tools: autotest: pull common MAVProxy options into common.py
This commit is contained in:
parent
b908af10b7
commit
b2cb6e196c
@ -28,20 +28,15 @@ HOME = mavutil.location(40.071374969556928,
|
||||
class AutoTestRover(AutoTest):
|
||||
def __init__(self,
|
||||
binary,
|
||||
viewerip=None,
|
||||
use_map=False,
|
||||
valgrind=False,
|
||||
gdb=False,
|
||||
speedup=10,
|
||||
frame=None,
|
||||
params=None,
|
||||
gdbserver=False):
|
||||
super(AutoTestRover, self).__init__()
|
||||
gdbserver=False,
|
||||
**kwargs):
|
||||
super(AutoTestRover, self).__init__(**kwargs)
|
||||
self.binary = binary
|
||||
self.options = ("--sitl=127.0.0.1:5501 --out=127.0.0.1:19550"
|
||||
" --streamrate=10")
|
||||
self.viewerip = viewerip
|
||||
self.use_map = use_map
|
||||
self.valgrind = valgrind
|
||||
self.gdb = gdb
|
||||
self.frame = frame
|
||||
@ -63,11 +58,6 @@ class AutoTestRover(AutoTest):
|
||||
if self.frame is None:
|
||||
self.frame = 'rover'
|
||||
|
||||
if self.viewerip:
|
||||
self.options += " --out=%s:14550" % self.viewerip
|
||||
if self.use_map:
|
||||
self.options += ' --map'
|
||||
|
||||
self.sitl = util.start_SITL(self.binary,
|
||||
wipe=True,
|
||||
model=self.frame,
|
||||
@ -103,8 +93,8 @@ class AutoTestRover(AutoTest):
|
||||
valgrind=self.valgrind,
|
||||
gdb=self.gdb,
|
||||
gdbserver=self.gdbserver)
|
||||
self.mavproxy = util.start_MAVProxy_SITL('APMrover2',
|
||||
options=self.options)
|
||||
self.mavproxy = util.start_MAVProxy_SITL(
|
||||
'APMrover2', options=self.mavproxy_options())
|
||||
self.mavproxy.expect('Telemetry log: (\S+)')
|
||||
logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % logfile)
|
||||
|
@ -30,21 +30,15 @@ AVCHOME = mavutil.location(40.072842, -105.230575, 1586, 0)
|
||||
|
||||
class AutoTestCopter(AutoTest):
|
||||
def __init__(self, binary,
|
||||
viewerip=None,
|
||||
use_map=False,
|
||||
valgrind=False,
|
||||
gdb=False,
|
||||
speedup=10,
|
||||
frame=None,
|
||||
params=None,
|
||||
gdbserver=False):
|
||||
super(AutoTestCopter, self).__init__()
|
||||
gdbserver=False,
|
||||
**kwargs):
|
||||
super(AutoTestCopter, self).__init__(**kwargs)
|
||||
self.binary = binary
|
||||
self.options = ('--sitl=127.0.0.1:5501 '
|
||||
' --out=127.0.0.1:19550 '
|
||||
' --streamrate=5')
|
||||
self.viewerip = viewerip
|
||||
self.use_map = use_map
|
||||
self.valgrind = valgrind
|
||||
self.gdb = gdb
|
||||
self.frame = frame
|
||||
@ -67,6 +61,15 @@ class AutoTestCopter(AutoTest):
|
||||
self.sitl = None
|
||||
self.hasInit = False
|
||||
|
||||
def mavproxy_options(self):
|
||||
ret = super(AutoTestCopter, self).mavproxy_options()
|
||||
if self.frame != 'heli':
|
||||
ret.append('--quadcopter')
|
||||
return ret
|
||||
|
||||
def sitl_streamrate(self):
|
||||
return 5
|
||||
|
||||
def init(self):
|
||||
if self.frame is None:
|
||||
self.frame = '+'
|
||||
@ -77,13 +80,6 @@ class AutoTestCopter(AutoTest):
|
||||
AVCHOME.lng,
|
||||
AVCHOME.alt,
|
||||
AVCHOME.heading)
|
||||
else:
|
||||
self.options += " --quadcopter"
|
||||
|
||||
if self.viewerip:
|
||||
self.options += " --out=%s:14550" % self.viewerip
|
||||
if self.use_map:
|
||||
self.options += ' --map'
|
||||
|
||||
self.sitl = util.start_SITL(self.binary,
|
||||
wipe=True,
|
||||
@ -120,8 +116,8 @@ class AutoTestCopter(AutoTest):
|
||||
valgrind=self.valgrind,
|
||||
gdb=self.gdb,
|
||||
gdbserver=self.gdbserver)
|
||||
self.mavproxy = util.start_MAVProxy_SITL('ArduCopter',
|
||||
options=self.options)
|
||||
self.mavproxy = util.start_MAVProxy_SITL(
|
||||
'ArduCopter', options=self.mavproxy_options())
|
||||
self.mavproxy.expect('Telemetry log: (\S+)')
|
||||
self.logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % self.logfile)
|
||||
@ -278,7 +274,7 @@ class AutoTestCopter(AutoTest):
|
||||
# TESTS FLY
|
||||
#################################################
|
||||
|
||||
# fly a square in stabilize mode
|
||||
# fly a square in alt_hold mode
|
||||
def fly_square(self, side=50, timeout=300):
|
||||
"""Fly a square, flying N then E ."""
|
||||
tstart = self.get_sim_time()
|
||||
|
@ -22,20 +22,15 @@ WIND = "0,180,0.2" # speed,direction,variance
|
||||
class AutoTestPlane(AutoTest):
|
||||
def __init__(self,
|
||||
binary,
|
||||
viewerip=None,
|
||||
use_map=False,
|
||||
valgrind=False,
|
||||
gdb=False,
|
||||
speedup=10,
|
||||
frame=None,
|
||||
params=None,
|
||||
gdbserver=False):
|
||||
super(AutoTestPlane, self).__init__()
|
||||
gdbserver=False,
|
||||
**kwargs):
|
||||
super(AutoTestPlane, self).__init__(**kwargs)
|
||||
self.binary = binary
|
||||
self.options = ('--sitl=127.0.0.1:5501 --out=127.0.0.1:19550'
|
||||
' --streamrate=10')
|
||||
self.viewerip = viewerip
|
||||
self.use_map = use_map
|
||||
self.valgrind = valgrind
|
||||
self.gdb = gdb
|
||||
self.frame = frame
|
||||
@ -57,11 +52,6 @@ class AutoTestPlane(AutoTest):
|
||||
if self.frame is None:
|
||||
self.frame = 'plane-elevrev'
|
||||
|
||||
if self.viewerip:
|
||||
self.options += " --out=%s:14550" % self.viewerip
|
||||
if self.use_map:
|
||||
self.options += ' --map'
|
||||
|
||||
defaults_file = os.path.join(testdir,
|
||||
'default_params/plane-jsbsim.parm')
|
||||
self.sitl = util.start_SITL(self.binary,
|
||||
@ -73,8 +63,8 @@ class AutoTestPlane(AutoTest):
|
||||
valgrind=self.valgrind,
|
||||
gdb=self.gdb,
|
||||
gdbserver=self.gdbserver)
|
||||
self.mavproxy = util.start_MAVProxy_SITL('ArduPlane',
|
||||
options=self.options)
|
||||
self.mavproxy = util.start_MAVProxy_SITL(
|
||||
'ArduPlane', options=self.mavproxy_options())
|
||||
self.mavproxy.expect('Telemetry log: (\S+)')
|
||||
logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % logfile)
|
||||
|
@ -21,20 +21,15 @@ HOME = mavutil.location(33.810313, -118.393867, 0, 185)
|
||||
class AutoTestSub(AutoTest):
|
||||
def __init__(self,
|
||||
binary,
|
||||
viewerip=None,
|
||||
use_map=False,
|
||||
valgrind=False,
|
||||
gdb=False,
|
||||
speedup=10,
|
||||
frame=None,
|
||||
params=None,
|
||||
gdbserver=False):
|
||||
super(AutoTestSub, self).__init__()
|
||||
gdbserver=False,
|
||||
**kwargs):
|
||||
super(AutoTestSub, self).__init__(**kwargs)
|
||||
self.binary = binary
|
||||
self.options = ('--sitl=127.0.0.1:5501 --out=127.0.0.1:19550'
|
||||
' --streamrate=10')
|
||||
self.viewerip = viewerip
|
||||
self.use_map = use_map
|
||||
self.valgrind = valgrind
|
||||
self.gdb = gdb
|
||||
self.frame = frame
|
||||
@ -56,11 +51,6 @@ class AutoTestSub(AutoTest):
|
||||
if self.frame is None:
|
||||
self.frame = 'vectored'
|
||||
|
||||
if self.viewerip:
|
||||
self.options += " --out=%s:14550" % self.viewerip
|
||||
if self.use_map:
|
||||
self.options += ' --map'
|
||||
|
||||
self.sitl = util.start_SITL(self.binary,
|
||||
wipe=True,
|
||||
model=self.frame,
|
||||
@ -96,8 +86,8 @@ class AutoTestSub(AutoTest):
|
||||
valgrind=self.valgrind,
|
||||
gdb=self.gdb,
|
||||
gdbserver=self.gdbserver)
|
||||
self.mavproxy = util.start_MAVProxy_SITL('ArduSub',
|
||||
options=self.options)
|
||||
self.mavproxy = util.start_MAVProxy_SITL(
|
||||
'ArduSub', options=self.mavproxy_options())
|
||||
self.mavproxy.expect('Telemetry log: (\S+)')
|
||||
logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % logfile)
|
||||
|
@ -32,9 +32,13 @@ class AutoTest(ABC):
|
||||
"""Base abstract class.
|
||||
It implements the common function for all vehicle types.
|
||||
"""
|
||||
def __init__(self):
|
||||
def __init__(self,
|
||||
viewerip=None,
|
||||
use_map=False):
|
||||
self.mavproxy = None
|
||||
self.mav = None
|
||||
self.viewerip = viewerip
|
||||
self.use_map = use_map
|
||||
|
||||
def progress(self, text):
|
||||
"""Display autotest progress text."""
|
||||
@ -53,6 +57,22 @@ class AutoTest(ABC):
|
||||
bits.append(path)
|
||||
return os.path.join(*bits)
|
||||
|
||||
def sitl_streamrate(self):
|
||||
'''allow subclasses to override SITL streamrate'''
|
||||
return 10
|
||||
|
||||
def mavproxy_options(self):
|
||||
'''returns options to be passed to MAVProxy'''
|
||||
ret = ['--sitl=127.0.0.1:5501',
|
||||
'--out=127.0.0.1:19550',
|
||||
'--streamrate=%u' % self.sitl_streamrate()]
|
||||
if self.viewerip:
|
||||
ret.append("--out=%s:14550" % self.viewerip)
|
||||
if self.use_map:
|
||||
ret.append('--map')
|
||||
|
||||
return ret
|
||||
|
||||
#################################################
|
||||
# GENERAL UTILITIES
|
||||
#################################################
|
||||
|
@ -246,7 +246,7 @@ def start_SITL(binary, valgrind=False, gdb=False, wipe=False,
|
||||
|
||||
|
||||
def start_MAVProxy_SITL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1:5760',
|
||||
options=None, logfile=sys.stdout):
|
||||
options=[], logfile=sys.stdout):
|
||||
"""Launch mavproxy connected to a SITL instance."""
|
||||
import pexpect
|
||||
global close_list
|
||||
@ -257,8 +257,7 @@ def start_MAVProxy_SITL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1
|
||||
if aircraft is None:
|
||||
aircraft = 'test.%s' % atype
|
||||
cmd += ' --aircraft=%s' % aircraft
|
||||
if options is not None:
|
||||
cmd += ' ' + options
|
||||
cmd += ' ' + ' '.join(options)
|
||||
ret = pexpect.spawn(cmd, logfile=logfile, encoding=ENCODING, timeout=60)
|
||||
ret.delaybeforesend = 0
|
||||
pexpect_autoclose(ret)
|
||||
|
@ -21,20 +21,15 @@ WIND = "0,180,0.2" # speed,direction,variance
|
||||
class AutoTestQuadPlane(AutoTest):
|
||||
def __init__(self,
|
||||
binary,
|
||||
viewerip=None,
|
||||
use_map=False,
|
||||
valgrind=False,
|
||||
gdb=False,
|
||||
speedup=10,
|
||||
frame=None,
|
||||
params=None,
|
||||
gdbserver=False):
|
||||
super(AutoTestQuadPlane, self).__init__()
|
||||
gdbserver=False,
|
||||
**kwargs):
|
||||
super(AutoTestQuadPlane, self).__init__(**kwargs)
|
||||
self.binary = binary
|
||||
self.options = ('--sitl=127.0.0.1:5501 --out=127.0.0.1:19550'
|
||||
' --streamrate=10')
|
||||
self.viewerip = viewerip
|
||||
self.use_map = use_map
|
||||
self.valgrind = valgrind
|
||||
self.gdb = gdb
|
||||
self.frame = frame
|
||||
@ -61,11 +56,6 @@ class AutoTestQuadPlane(AutoTest):
|
||||
if self.frame is None:
|
||||
self.frame = 'quadplane'
|
||||
|
||||
if self.viewerip:
|
||||
self.options += " --out=%s:14550" % self.viewerip
|
||||
if self.use_map:
|
||||
self.options += ' --map'
|
||||
|
||||
defaults_file = os.path.join(testdir, 'default_params/quadplane.parm')
|
||||
self.sitl = util.start_SITL(self.binary,
|
||||
wipe=True,
|
||||
@ -76,8 +66,8 @@ class AutoTestQuadPlane(AutoTest):
|
||||
valgrind=self.valgrind,
|
||||
gdb=self.gdb,
|
||||
gdbserver=self.gdbserver)
|
||||
self.mavproxy = util.start_MAVProxy_SITL('QuadPlane',
|
||||
options=self.options)
|
||||
self.mavproxy = util.start_MAVProxy_SITL(
|
||||
'QuadPlane', options=self.mavproxy_options())
|
||||
self.mavproxy.expect('Telemetry log: (\S+)')
|
||||
logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % logfile)
|
||||
|
Loading…
Reference in New Issue
Block a user