Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/autotest/test_param_upgrade.py
Views: 1798
#!/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" # noqa67AP_FLAKE8_CLEAN8'''910import vehicle_test_suite11import os12import sys13import argparse14import subprocess15import time16import shutil17import string18import pathlib1920from pysim import util212223class ParamChange():24def __init__(self, old_name, old_value, new_name, new_value):25self.old_name = old_name26self.old_value = old_value27self.new_name = new_name28self.new_value = new_value2930def __str__(self):31return f"{self.old_name}={self.old_value}->{self.new_name}={self.new_value}"323334class TestParamUpgradeTestSuiteSetParameters(vehicle_test_suite.TestSuite):35def __init__(self, binary, param_changes):36super(TestParamUpgradeTestSuiteSetParameters, self).__init__(binary)37self.param_changes = param_changes3839def sysid_thismav(self):40if "antennatracker" in self.binary:41return 242return super(TestParamUpgradeTestSuiteSetParameters, self).sysid_thismav()4344def vehicleinfo_key(self):45'''magically guess vehicleinfo_key from filepath'''46path = self.binary.lower()47if "plane" in path:48return "ArduPlane"49if "copter" in path:50return "ArduCopter"51raise ValueError("Can't determine vehicleinfo_key from binary path")5253def model(self):54path = self.binary.lower()55if "plane" in path:56return "quadplane"57if "copter" in path:58return "X"59raise ValueError("Can't determine vehicleinfo_key from binary path")6061def run(self):62self.start_SITL(63binary=self.binary,64model=self.model(),65wipe=True,66sitl_home="1,1,1,1",67)68self.get_mavlink_connection_going()6970sets = {}71for param_change in param_changes:72sets[param_change.old_name] = param_change.old_value73self.set_parameters(sets)7475# stopping SITL too soon can leave eeprom.bin corrupt!76self.delay_sim_time(2) # FIXTHAT, should not be needed!7778self.stop_SITL()798081class TestParamUpgradeTestSuiteCheckParameters(vehicle_test_suite.TestSuite):82def __init__(self, binary, param_changes, epsilon=0.0001):83super(TestParamUpgradeTestSuiteCheckParameters, self).__init__(binary)84self.param_changes = param_changes85self.epsilon = epsilon8687def sysid_thismav(self):88if "antennatracker" in self.binary:89return 290return super(TestParamUpgradeTestSuiteCheckParameters, self).sysid_thismav()9192def vehicleinfo_key(self):93'''magically guess vehicleinfo_key from filepath'''94path = self.binary.lower()95if "plane" in path:96return "ArduPlane"97if "copter" in path:98return "ArduCopter"99raise ValueError("Can't determine vehicleinfo_key from binary path")100101def model(self):102path = self.binary.lower()103if "plane" in path:104return "quadplane"105if "copter" in path:106return "X"107raise ValueError("Can't determine vehicleinfo_key from binary path")108109def run(self):110self.start_SITL(111binary=self.binary,112model=self.model(),113sitl_home="1,1,1,1",114wipe=False,115)116self.get_mavlink_connection_going()117118params_to_check = [x.new_name for x in self.param_changes]119fetched_params = self.get_parameters(params_to_check)120121for p in self.param_changes:122if abs(fetched_params[p.new_name] - p.new_value) > self.epsilon:123raise 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]}") # noqa124125print(f"OK: {p.old_name}={p.old_value} converted to {p.new_name}={p.new_value}")126127self.stop_SITL()128129130class TestParamUpgradeForVehicle():131def __init__(self,132vehicle,133param_changes,134branch=None,135master_branch="master",136run_eedump_before=False,137run_eedump_after=False,138):139self.vehicle = vehicle140self.master_branch = master_branch141self.branch = branch142self.param_changes = param_changes143self.run_eedump_before = run_eedump_before144self.run_eedump_after = run_eedump_after145146def run_program(self, prefix, cmd_list, show_output=True, env=None, show_output_on_error=True, show_command=None, cwd="."):147if show_command is None:148show_command = True149if show_command:150cmd = " ".join(cmd_list)151if cwd is None:152cwd = "."153self.progress(f"Running ({cmd}) in ({cwd})")154p = subprocess.Popen(155cmd_list,156stdin=None,157stdout=subprocess.PIPE,158close_fds=True,159stderr=subprocess.STDOUT,160cwd=cwd,161env=env)162output = ""163while True:164x = p.stdout.readline()165if len(x) == 0:166returncode = os.waitpid(p.pid, 0)167if returncode:168break169# select not available on Windows... probably...170time.sleep(0.1)171continue172x = bytearray(x)173x = filter(lambda x : chr(x) in string.printable, x)174x = "".join([chr(c) for c in x])175output += x176x = x.rstrip()177some_output = "%s: %s" % (prefix, x)178if show_output:179print(some_output)180else:181output += some_output182(_, status) = returncode183if status != 0:184if not show_output and show_output_on_error:185# we were told not to show output, but we just186# failed... so show output...187print(output)188self.progress("Process failed (%s)" %189str(returncode))190try:191path = pathlib.Path(self.tmpdir, f"process-failure-{int(time.time())}")192path.write_text(output)193self.progress("Wrote process failure file (%s)" % path)194except Exception:195self.progress("Writing process failure file failed")196raise subprocess.CalledProcessError(197returncode, cmd_list)198return output199200def find_current_git_branch_or_sha1(self):201try:202output = self.run_git(["symbolic-ref", "--short", "HEAD"])203output = output.strip()204return output205except subprocess.CalledProcessError:206pass207208# probably in a detached-head state. Get a sha1 instead:209output = self.run_git(["rev-parse", "--short", "HEAD"])210output = output.strip()211return output212213def find_git_branch_merge_base(self, branch, master_branch):214output = self.run_git(["merge-base", branch, master_branch])215output = output.strip()216return output217218def run_git(self, args, show_output=True, source_dir=None):219'''run git with args git_args; returns git's output'''220cmd_list = ["git"]221cmd_list.extend(args)222return self.run_program("TPU-GIT", cmd_list, show_output=show_output, cwd=source_dir)223224def progress(self, string):225'''pretty-print progress'''226print("TPU: %s" % string)227228def binary_path(self, vehicle):229build_subdir = "sitl"230if 'AP_Periph' in vehicle:231build_subdir = "sitl_periph_universal"232return f"build/{build_subdir}/{self.build_target_name(vehicle)}"233234def build_target_name(self, vehicle):235binary_name = vehicle236if binary_name == 'heli':237binary_name = 'arducopter-heli'238if binary_name == 'rover':239binary_name = 'ardurover'240return f"bin/{binary_name}"241242def run_eedump(self):243self.run_program("TPU-EED", [244"libraries/AP_Param/tools/eedump_apparam",245"eeprom.bin"246])247248def run(self):249branch = self.branch250if branch is None:251branch = self.find_current_git_branch_or_sha1()252253master_commit = self.master_branch254255self.use_merge_base = True256if self.use_merge_base:257master_commit = self.find_git_branch_merge_base(branch, self.master_branch)258self.progress("Using merge base (%s)" % master_commit)259260self.run_git(["checkout", master_commit], show_output=False)261self.run_git(["submodule", "update", "--recursive"], show_output=False)262shutil.rmtree("build", ignore_errors=True)263board = "sitl"264if "AP_Periph" in self.vehicle:265board = "sitl_periph_universal"266util.build_SITL(267self.build_target_name(self.vehicle),268board=board,269clean=False,270configure=True,271)272suite = TestParamUpgradeTestSuiteSetParameters(self.binary_path(self.vehicle), self.param_changes)273suite.run()274275self.run_git(["checkout", branch], show_output=False)276self.run_git(["submodule", "update", "--recursive"], show_output=False)277shutil.rmtree("build", ignore_errors=True)278util.build_SITL(279self.build_target_name(self.vehicle),280board=board,281clean=False,282configure=True,283)284suite = TestParamUpgradeTestSuiteCheckParameters(self.binary_path(self.vehicle), self.param_changes)285286if self.run_eedump_before:287self.run_eedump()288289# this call starts SITL which will do the upgrade:290suite.run()291292if self.run_eedump_after:293self.run_eedump()294295296class TestParamUpgrade():297def __init__(self,298param_changes,299vehicles=None,300run_eedump_before=False,301run_eedump_after=False,302master_branch="master",303):304self.vehicles = vehicles305self.param_changes = param_changes306self.vehicles = vehicles307self.run_eedump_before = run_eedump_before308self.run_eedump_after = run_eedump_after309self.master_branch = master_branch310311if self.vehicles is None:312self.vehicles = self.all_vehicles()313314def all_vehicles(self):315return [316# 'AP_Periph',317'arducopter',318'arduplane',319'antennatracker',320'heli',321'rover',322'blimp',323'ardusub',324]325326def run(self):327for vehicle in self.vehicles:328s = TestParamUpgradeForVehicle(329vehicle,330self.param_changes,331run_eedump_before=self.run_eedump_before,332run_eedump_after=self.run_eedump_after,333master_branch=self.master_branch,334)335s.run()336337338if __name__ == "__main__":339''' main program '''340os.environ['PYTHONUNBUFFERED'] = '1'341342if sys.platform != "darwin":343os.putenv('TMPDIR', util.reltopdir('tmp'))344345parser = argparse.ArgumentParser("test_param_upgrade.py")346parser.add_argument(347"--param",348action='append',349default=[],350help="PARAM=VALUE pair to test upgrade for, or PARAM=VALUE->NEWPARAM=NEWVALUE",351)352parser.add_argument(353"--vehicle",354action='append',355default=[],356help="vehicle to test",357)358parser.add_argument(359"--run-eedump-before",360action='store_true',361default=False,362help="run the (already-compiled) eedump tool on eeprom.bin before doing conversion",363)364parser.add_argument(365"--run-eedump-after",366action='store_true',367default=False,368help="run the (already-compiled) eedump tool on eeprom.bin after doing conversion",369)370parser.add_argument(371"--master-branch",372type=str,373default="master",374help="master branch to use",375)376args = parser.parse_args()377378param_changes = []379for x in args.param:380if "->" in x:381(old, new) = x.split("->")382(old_name, old_value) = old.split("=")383(new_name, new_value) = new.split("=")384param_changes.append(ParamChange(old_name, float(old_value), new_name, float(new_value)))385386else:387(name, value) = x.split("=")388param_changes.append(ParamChange(name, float(value), name, float(value)))389390vehicles = args.vehicle391392if 'AP_Periph' in vehicles:393raise ValueError("AP_Periph not supported yet")394395if len(vehicles) == 0:396vehicles = None397398x = TestParamUpgrade(399param_changes,400vehicles=vehicles,401run_eedump_before=args.run_eedump_before,402run_eedump_after=args.run_eedump_after,403master_branch=args.master_branch,404)405x.run()406407408