Path: blob/master/Tools/autotest/test_param_upgrade.py
9660 views
#!/usr/bin/env python312'''3Test parameter upgrade, master vs branch45./Tools/autotest/test_param_upgrade.py --vehicle=arduplane --param "GPS_TYPE=17->GPS1_TYPE=17" --param "GPS_TYPE2=37->GPS2_TYPE=37" --param "GPS_GNSS_MODE=21->GPS1_GNSS_MODE=21" --param "GPS_GNSS_MODE2=45->GPS2_GNSS_MODE=45" --param "GPS_RATE_MS=186->GPS1_RATE_MS=186" --param "GPS_RATE_MS2=123->GPS2_RATE_MS=123" --param "GPS_POS1_X=3.75->GPS1_POS_X=3.75" --param "GPS_POS2_X=6.9->GPS2_POS_X=6.9" --param "GPS_POS1_Y=2.75->GPS1_POS_Y=2.75" --param "GPS_POS2_Y=5.9->GPS2_POS_Y=5.9" --param "GPS_POS1_Z=12.1->GPS1_POS_Z=12.1" --param "GPS_POS2_Z=-6.9->GPS2_POS_Z=-6.9" --param "GPS_DELAY_MS=987->GPS1_DELAY_MS=987" --param "GPS_DELAY_MS2=2345->GPS2_DELAY_MS=2345" --param "GPS_COM_PORT=19->GPS1_COM_PORT=19" --param "GPS_COM_PORT2=100->GPS2_COM_PORT=100" --param "GPS_CAN_NODEID1=109->GPS1_CAN_NODEID=109" --param "GPS_CAN_NODEID2=102->GPS2_CAN_NODEID=102" --param "GPS1_CAN_OVRIDE=34->GPS1_CAN_OVRIDE=34" --param "GPS2_CAN_OVRIDE=67" --param "GPS_MB1_TYPE=1->GPS1_MB_TYPE=1" --param "GPS_MB1_OFS_X=3.14->GPS1_MB_OFS_X=3.14" --param "GPS_MB1_OFS_Y=2.18->GPS1_MB_OFS_Y=2.18" --param "GPS_MB1_OFS_Z=17.6->GPS1_MB_OFS_Z=17.6" --param "GPS_MB2_TYPE=13->GPS2_MB_TYPE=13" --param "GPS_MB2_OFS_X=17.14->GPS2_MB_OFS_X=17.14" --param "GPS_MB2_OFS_Y=12.18->GPS2_MB_OFS_Y=12.18" --param "GPS_MB2_OFS_Z=27.6->GPS2_MB_OFS_Z=27.6" # noqa67./Tools/autotest/test_param_upgrade.py --vehicle=arduplane --param "SERIAL1_OPTIONS=1024->MAV2_OPTIONS=2" --param "SERIAL2_OPTIONS=4096->MAV3_OPTIONS=4"8./Tools/autotest/test_param_upgrade.py --vehicle=arduplane --param "SERIAL1_OPTIONS=5120->MAV2_OPTIONS=6"910AP_FLAKE8_CLEAN11'''1213import vehicle_test_suite14import os15import sys16import argparse17import subprocess18import time19import shutil20import string21import pathlib2223from pysim import util242526class ParamChange():27def __init__(self, old_name, old_value, new_name, new_value):28self.old_name = old_name29self.old_value = old_value30self.new_name = new_name31self.new_value = new_value3233def __str__(self):34return f"{self.old_name}={self.old_value}->{self.new_name}={self.new_value}"353637class TestParamUpgradeTestSuite(vehicle_test_suite.TestSuite):38def __init__(self, binary):39super(TestParamUpgradeTestSuite, self).__init__(binary)4041def sysid_thismav(self):42if "antennatracker" in self.binary:43return 244return super(TestParamUpgradeTestSuite, self).sysid_thismav()4546def vehicleinfo_key(self):47'''magically guess vehicleinfo_key from filepath'''48path = self.binary.lower()49if "blimp" in path:50return "Blimp"51if "copter" in path:52return "ArduCopter"53if "plane" in path:54return "ArduPlane"55if "rover" in path:56return "Rover"57if "sub" in path:58return "ArduSub"59if "tracker" in path:60return "AntennaTracker"61raise ValueError(f"Can't determine vehicleinfo_key from binary path {path}")6263def model(self):64path = self.binary.lower()65if "blimp" in path:66return "blimp"67if "copter" in path:68return "X"69if "plane" in path:70return "quadplane"71if "rover" in path:72return "rover"73if "sub" in path:74return "vectored"75if "tracker" in path:76return "tracker"77raise ValueError(f"Can't determine model from binary path {path}")787980class TestParamUpgradeTestSuiteSetParameters(TestParamUpgradeTestSuite):81def __init__(self, binary, param_changes):82super(TestParamUpgradeTestSuiteSetParameters, self).__init__(binary)83self.param_changes = param_changes8485def run(self):86self.start_SITL(87binary=self.binary,88model=self.model(),89wipe=True,90sitl_home="1,1,1,1",91)92self.get_mavlink_connection_going()9394sets = {}95for param_change in param_changes:96sets[param_change.old_name] = param_change.old_value97self.set_parameters(sets)9899# stopping SITL too soon can leave eeprom.bin corrupt!100self.delay_sim_time(2) # FIXTHAT, should not be needed!101102self.stop_SITL()103104105class TestParamUpgradeTestSuiteCheckParameters(TestParamUpgradeTestSuite):106def __init__(self, binary, param_changes, epsilon=0.0001):107super(TestParamUpgradeTestSuiteCheckParameters, self).__init__(binary)108self.param_changes = param_changes109self.epsilon = epsilon110111def run(self):112self.start_SITL(113binary=self.binary,114model=self.model(),115sitl_home="1,1,1,1",116wipe=False,117)118self.get_mavlink_connection_going()119120params_to_check = [x.new_name for x in self.param_changes]121fetched_params = self.get_parameters(params_to_check)122123for p in self.param_changes:124if abs(fetched_params[p.new_name] - p.new_value) > self.epsilon:125raise ValueError(f"{p.old_name}={p.old_value} did not convert into {p.new_name}={p.new_value}, got {p.new_name}={fetched_params[p.new_name]}") # noqa126127print(f"OK: {p.old_name}={p.old_value} converted to {p.new_name}={p.new_value}")128129self.stop_SITL()130131132class TestParamUpgradeForVehicle():133def __init__(self,134vehicle,135param_changes,136branch=None,137master_branch="master",138run_eedump_before=False,139run_eedump_after=False,140):141self.vehicle = vehicle142self.master_branch = master_branch143self.branch = branch144self.param_changes = param_changes145self.run_eedump_before = run_eedump_before146self.run_eedump_after = run_eedump_after147148def run_program(self, prefix, cmd_list, show_output=True, env=None, show_output_on_error=True, show_command=None, cwd="."):149if show_command is None:150show_command = True151if show_command:152cmd = " ".join(cmd_list)153if cwd is None:154cwd = "."155self.progress(f"Running ({cmd}) in ({cwd})")156p = subprocess.Popen(157cmd_list,158stdin=None,159stdout=subprocess.PIPE,160close_fds=True,161stderr=subprocess.STDOUT,162cwd=cwd,163env=env)164output = ""165while True:166x = p.stdout.readline()167if len(x) == 0:168returncode = os.waitpid(p.pid, 0)169if returncode:170break171# select not available on Windows... probably...172time.sleep(0.1)173continue174x = bytearray(x)175x = filter(lambda x : chr(x) in string.printable, x)176x = "".join([chr(c) for c in x])177output += x178x = x.rstrip()179some_output = "%s: %s" % (prefix, x)180if show_output:181print(some_output)182else:183output += some_output184(_, status) = returncode185if status != 0:186if not show_output and show_output_on_error:187# we were told not to show output, but we just188# failed... so show output...189print(output)190self.progress("Process failed (%s)" %191str(returncode))192try:193path = pathlib.Path(self.tmpdir, f"process-failure-{int(time.time())}")194path.write_text(output)195self.progress("Wrote process failure file (%s)" % path)196except Exception:197self.progress("Writing process failure file failed")198raise subprocess.CalledProcessError(199returncode, cmd_list)200return output201202def find_current_git_branch_or_sha1(self):203try:204output = self.run_git(["symbolic-ref", "--short", "HEAD"])205output = output.strip()206return output207except subprocess.CalledProcessError:208pass209210# probably in a detached-head state. Get a sha1 instead:211output = self.run_git(["rev-parse", "--short", "HEAD"])212output = output.strip()213return output214215def find_git_branch_merge_base(self, branch, master_branch):216output = self.run_git(["merge-base", branch, master_branch])217output = output.strip()218return output219220def run_git(self, args, show_output=True, source_dir=None):221'''run git with args git_args; returns git's output'''222cmd_list = ["git"]223cmd_list.extend(args)224return self.run_program("TPU-GIT", cmd_list, show_output=show_output, cwd=source_dir)225226def progress(self, string):227'''pretty-print progress'''228print("TPU: %s" % string)229230def binary_path(self, vehicle):231build_subdir = "sitl"232if 'AP_Periph' in vehicle:233build_subdir = "sitl_periph_universal"234return f"build/{build_subdir}/{self.build_target_name(vehicle)}"235236def build_target_name(self, vehicle):237binary_name = vehicle238if binary_name == 'heli':239binary_name = 'arducopter-heli'240if binary_name == 'rover':241binary_name = 'ardurover'242return f"bin/{binary_name}"243244def run_eedump(self):245self.run_program("TPU-EED", [246"libraries/AP_Param/tools/eedump_apparam",247"eeprom.bin"248])249250def run(self):251branch = self.branch252if branch is None:253branch = self.find_current_git_branch_or_sha1()254255master_commit = self.master_branch256257self.use_merge_base = True258if self.use_merge_base:259master_commit = self.find_git_branch_merge_base(branch, self.master_branch)260self.progress("Using merge base (%s)" % master_commit)261262self.run_git(["checkout", master_commit], show_output=False)263self.run_git(["submodule", "update", "--recursive"], show_output=False)264shutil.rmtree("build", ignore_errors=True)265board = "sitl"266if "AP_Periph" in self.vehicle:267board = "sitl_periph_universal"268util.build_SITL(269self.build_target_name(self.vehicle),270board=board,271clean=False,272configure=True,273)274suite = TestParamUpgradeTestSuiteSetParameters(self.binary_path(self.vehicle), self.param_changes)275suite.run()276277self.run_git(["checkout", branch], show_output=False)278self.run_git(["submodule", "update", "--recursive"], show_output=False)279shutil.rmtree("build", ignore_errors=True)280util.build_SITL(281self.build_target_name(self.vehicle),282board=board,283clean=False,284configure=True,285)286suite = TestParamUpgradeTestSuiteCheckParameters(self.binary_path(self.vehicle), self.param_changes)287288if self.run_eedump_before:289self.run_eedump()290291# this call starts SITL which will do the upgrade:292suite.run()293294if self.run_eedump_after:295self.run_eedump()296297298class TestParamUpgrade():299def __init__(self,300param_changes,301vehicles=None,302run_eedump_before=False,303run_eedump_after=False,304master_branch="master",305):306self.vehicles = vehicles307self.param_changes = param_changes308self.vehicles = vehicles309self.run_eedump_before = run_eedump_before310self.run_eedump_after = run_eedump_after311self.master_branch = master_branch312313if self.vehicles is None:314self.vehicles = self.all_vehicles()315316def all_vehicles(self):317return [318# 'AP_Periph',319'arducopter',320'arduplane',321'antennatracker',322'heli',323'rover',324'blimp',325'ardusub',326]327328def run(self):329for vehicle in self.vehicles:330s = TestParamUpgradeForVehicle(331vehicle,332self.param_changes,333run_eedump_before=self.run_eedump_before,334run_eedump_after=self.run_eedump_after,335master_branch=self.master_branch,336)337s.run()338339340if __name__ == "__main__":341''' main program '''342os.environ['PYTHONUNBUFFERED'] = '1'343344if sys.platform != "darwin":345os.putenv('TMPDIR', util.reltopdir('tmp'))346347parser = argparse.ArgumentParser("test_param_upgrade.py")348parser.add_argument(349"--param",350action='append',351default=[],352help="PARAM=VALUE pair to test upgrade for, or PARAM=VALUE->NEWPARAM=NEWVALUE",353)354parser.add_argument(355"--vehicle",356action='append',357default=[],358help="vehicle to test",359)360parser.add_argument(361"--run-eedump-before",362action='store_true',363default=False,364help="run the (already-compiled) eedump tool on eeprom.bin before doing conversion",365)366parser.add_argument(367"--run-eedump-after",368action='store_true',369default=False,370help="run the (already-compiled) eedump tool on eeprom.bin after doing conversion",371)372parser.add_argument(373"--master-branch",374type=str,375default="master",376help="master branch to use",377)378args = parser.parse_args()379380param_changes = []381for x in args.param:382if "->" in x:383(old, new) = x.split("->")384(old_name, old_value) = old.split("=")385(new_name, new_value) = new.split("=")386param_changes.append(ParamChange(old_name, float(old_value), new_name, float(new_value)))387388else:389(name, value) = x.split("=")390param_changes.append(ParamChange(name, float(value), name, float(value)))391392vehicles = args.vehicle393394if 'AP_Periph' in vehicles:395raise ValueError("AP_Periph not supported yet")396397if len(vehicles) == 0:398vehicles = None399400x = TestParamUpgrade(401param_changes,402vehicles=vehicles,403run_eedump_before=args.run_eedump_before,404run_eedump_after=args.run_eedump_after,405master_branch=args.master_branch,406)407x.run()408409410