mirror of https://github.com/ArduPilot/ardupilot
autotest: remove generation of defaults files
these were never particularly useful, and now we can actually retrieve the defaults from the running vehicle, so this is even less useful.
This commit is contained in:
parent
c733872435
commit
4317a40fef
|
@ -34,7 +34,6 @@ import helicopter
|
||||||
|
|
||||||
import examples
|
import examples
|
||||||
from pysim import util
|
from pysim import util
|
||||||
from pymavlink import mavutil
|
|
||||||
from pymavlink.generator import mavtemplate
|
from pymavlink.generator import mavtemplate
|
||||||
|
|
||||||
from common import Test
|
from common import Test
|
||||||
|
@ -59,47 +58,6 @@ def buildlogs_path(path):
|
||||||
return os.path.join(*bits)
|
return os.path.join(*bits)
|
||||||
|
|
||||||
|
|
||||||
def get_default_params(atype, binary):
|
|
||||||
"""Get default parameters."""
|
|
||||||
# use rover simulator so SITL is not starved of input
|
|
||||||
HOME = mavutil.location(40.071374969556928,
|
|
||||||
-105.22978898137808,
|
|
||||||
1583.702759,
|
|
||||||
246)
|
|
||||||
if "plane" in binary or "rover" in binary:
|
|
||||||
frame = "rover"
|
|
||||||
else:
|
|
||||||
frame = "+"
|
|
||||||
|
|
||||||
home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading)
|
|
||||||
mavproxy_master = 'tcp:127.0.0.1:5760'
|
|
||||||
sitl = util.start_SITL(binary,
|
|
||||||
wipe=True,
|
|
||||||
model=frame,
|
|
||||||
home=home,
|
|
||||||
speedup=10,
|
|
||||||
unhide_parameters=True)
|
|
||||||
mavproxy = util.start_MAVProxy_SITL(atype,
|
|
||||||
master=mavproxy_master)
|
|
||||||
print("Dumping defaults")
|
|
||||||
idx = mavproxy.expect([r'Saved [0-9]+ parameters to (\S+)'])
|
|
||||||
if idx == 0:
|
|
||||||
# we need to restart it after eeprom erase
|
|
||||||
util.pexpect_close(mavproxy)
|
|
||||||
util.pexpect_close(sitl)
|
|
||||||
sitl = util.start_SITL(binary, model=frame, home=home, speedup=10)
|
|
||||||
mavproxy = util.start_MAVProxy_SITL(atype,
|
|
||||||
master=mavproxy_master)
|
|
||||||
mavproxy.expect(r'Saved [0-9]+ parameters to (\S+)')
|
|
||||||
parmfile = mavproxy.match.group(1)
|
|
||||||
dest = buildlogs_path('%s-defaults.parm' % atype)
|
|
||||||
shutil.copy(parmfile, dest)
|
|
||||||
util.pexpect_close(mavproxy)
|
|
||||||
util.pexpect_close(sitl)
|
|
||||||
print("Saved defaults for %s to %s" % (atype, dest))
|
|
||||||
return True
|
|
||||||
|
|
||||||
|
|
||||||
def build_all_filepath():
|
def build_all_filepath():
|
||||||
"""Get build_all.sh path."""
|
"""Get build_all.sh path."""
|
||||||
return util.reltopdir('Tools/scripts/build_all.sh')
|
return util.reltopdir('Tools/scripts/build_all.sh')
|
||||||
|
@ -504,10 +462,6 @@ def run_step(step):
|
||||||
|
|
||||||
binary = binary_path(step, debug=opts.debug)
|
binary = binary_path(step, debug=opts.debug)
|
||||||
|
|
||||||
if step.startswith("defaults"):
|
|
||||||
vehicle = step[9:]
|
|
||||||
return get_default_params(vehicle, binary)
|
|
||||||
|
|
||||||
# see if we need any supplementary binaries
|
# see if we need any supplementary binaries
|
||||||
supplementary_binaries = []
|
supplementary_binaries = []
|
||||||
for k in supplementary_test_binary_map.keys():
|
for k in supplementary_test_binary_map.keys():
|
||||||
|
@ -706,9 +660,10 @@ def write_fullresults():
|
||||||
results.addglob("GPX track", '*.gpx')
|
results.addglob("GPX track", '*.gpx')
|
||||||
|
|
||||||
# results common to all vehicles:
|
# results common to all vehicles:
|
||||||
vehicle_files = [('{vehicle} defaults', '{vehicle}-defaults.parm'),
|
vehicle_files = [
|
||||||
('{vehicle} core', '{vehicle}.core'),
|
('{vehicle} core', '{vehicle}.core'),
|
||||||
('{vehicle} ELF', '{vehicle}.elf'), ]
|
('{vehicle} ELF', '{vehicle}.elf'),
|
||||||
|
]
|
||||||
vehicle_globs = [('{vehicle} log', '{vehicle}-*.BIN'), ]
|
vehicle_globs = [('{vehicle} log', '{vehicle}-*.BIN'), ]
|
||||||
for vehicle in all_vehicles():
|
for vehicle in all_vehicles():
|
||||||
subs = {'vehicle': vehicle}
|
subs = {'vehicle': vehicle}
|
||||||
|
@ -1104,33 +1059,27 @@ if __name__ == "__main__":
|
||||||
'run.examples',
|
'run.examples',
|
||||||
|
|
||||||
'build.Plane',
|
'build.Plane',
|
||||||
'defaults.Plane',
|
|
||||||
'test.Plane',
|
'test.Plane',
|
||||||
'test.QuadPlane',
|
'test.QuadPlane',
|
||||||
|
|
||||||
'build.Rover',
|
'build.Rover',
|
||||||
'defaults.Rover',
|
|
||||||
'test.Rover',
|
'test.Rover',
|
||||||
'test.BalanceBot',
|
'test.BalanceBot',
|
||||||
'test.Sailboat',
|
'test.Sailboat',
|
||||||
|
|
||||||
'build.Copter',
|
'build.Copter',
|
||||||
'defaults.Copter',
|
|
||||||
'test.Copter',
|
'test.Copter',
|
||||||
|
|
||||||
'build.Helicopter',
|
'build.Helicopter',
|
||||||
'test.Helicopter',
|
'test.Helicopter',
|
||||||
|
|
||||||
'build.Tracker',
|
'build.Tracker',
|
||||||
'defaults.Tracker',
|
|
||||||
'test.Tracker',
|
'test.Tracker',
|
||||||
|
|
||||||
'build.Sub',
|
'build.Sub',
|
||||||
'defaults.Sub',
|
|
||||||
'test.Sub',
|
'test.Sub',
|
||||||
|
|
||||||
'build.Blimp',
|
'build.Blimp',
|
||||||
'defaults.Blimp',
|
|
||||||
'test.Blimp',
|
'test.Blimp',
|
||||||
|
|
||||||
'build.SITLPeriphGPS',
|
'build.SITLPeriphGPS',
|
||||||
|
@ -1172,11 +1121,6 @@ if __name__ == "__main__":
|
||||||
"drive.balancebot": "test.BalanceBot",
|
"drive.balancebot": "test.BalanceBot",
|
||||||
"fly.CopterAVC": "test.Helicopter",
|
"fly.CopterAVC": "test.Helicopter",
|
||||||
"test.AntennaTracker": "test.Tracker",
|
"test.AntennaTracker": "test.Tracker",
|
||||||
"defaults.ArduCopter": "defaults.Copter",
|
|
||||||
"defaults.ArduPlane": "defaults.Plane",
|
|
||||||
"defaults.ArduSub": "defaults.Sub",
|
|
||||||
"defaults.APMrover2": "defaults.Rover",
|
|
||||||
"defaults.AntennaTracker": "defaults.Tracker",
|
|
||||||
"fly.ArduCopterTests1a": "test.CopterTests1a",
|
"fly.ArduCopterTests1a": "test.CopterTests1a",
|
||||||
"fly.ArduCopterTests1b": "test.CopterTests1b",
|
"fly.ArduCopterTests1b": "test.CopterTests1b",
|
||||||
"fly.ArduCopterTests1c": "test.CopterTests1c",
|
"fly.ArduCopterTests1c": "test.CopterTests1c",
|
||||||
|
|
Loading…
Reference in New Issue