From 3d431cd4f17dfe8462e7b8935e090e0ae74fd59d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 15 Jan 2021 16:13:01 +1100 Subject: [PATCH] autotest: ensure defaults files don't set already-default-values autotest: mark some vehicles as having external physics models autotest: add default_params_filename to some vehicle info --- Tools/autotest/antennatracker.py | 6 ++- Tools/autotest/arducopter.py | 12 ++++-- Tools/autotest/arduplane.py | 6 ++- Tools/autotest/ardusub.py | 1 + Tools/autotest/common.py | 59 ++++++++++++++++++++++++++++- Tools/autotest/pysim/vehicleinfo.py | 10 +++++ Tools/autotest/quadplane.py | 6 ++- Tools/autotest/rover.py | 6 ++- 8 files changed, 93 insertions(+), 13 deletions(-) diff --git a/Tools/autotest/antennatracker.py b/Tools/autotest/antennatracker.py index 488c07d474..3e2be3cb6c 100644 --- a/Tools/autotest/antennatracker.py +++ b/Tools/autotest/antennatracker.py @@ -149,10 +149,12 @@ class AutoTestTracker(AutoTest): comparator=operator.le) def disabled_tests(self): - return { + ret = super(AutoTestTracker, self).disabled_tests() + ret.update({ "ArmFeatures": "See https://github.com/ArduPilot/ardupilot/issues/10652", "CPUFailsafe": " tracker doesn't have a CPU failsafe", - } + }) + return ret def tests(self): '''return list of all tests''' diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index cf68621e8e..1fb227b22d 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -6274,11 +6274,13 @@ class AutoTestCopter(AutoTest): return ret def disabled_tests(self): - return { + ret = super(AutoTestCopter, self).disabled_tests() + ret.update({ "Parachute": "See https://github.com/ArduPilot/ardupilot/issues/4702", "HorizontalAvoidFence": "See https://github.com/ArduPilot/ardupilot/issues/11525", "AltEstimation": "See https://github.com/ArduPilot/ardupilot/issues/15191", - } + }) + return ret class AutoTestHeli(AutoTestCopter): @@ -6577,9 +6579,11 @@ class AutoTestHeli(AutoTestCopter): return ret def disabled_tests(self): - return { + ret = super(AutoTestHeli, self).disabled_tests() + ret.update({ "SplineWaypoint": "See https://github.com/ArduPilot/ardupilot/issues/14593", - } + }) + return ret class AutoTestCopterTests1(AutoTestCopter): def tests(self): diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index ffcff890e3..e260d40227 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -2204,5 +2204,7 @@ class AutoTestPlane(AutoTest): return ret def disabled_tests(self): - return { - } + ret = super(AutoTestPlane, self).disabled_tests() + ret.update({ + }) + return ret diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index b88d216d86..126417c40e 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -342,6 +342,7 @@ class AutoTestSub(AutoTest): ret = super(AutoTestSub, self).disabled_tests() ret.update({ "ConfigErrorLoop": "Sub does not instantiate AP_Stats. Also see https://github.com/ArduPilot/ardupilot/issues/10247", + "FrameDefaults": "Sub maintainers want all values in files", }) return ret diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 2c67b59bce..8c29e1a9cd 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -7828,7 +7828,9 @@ switch value''' self.test_parameters_download() def disabled_tests(self): - return {} + return { + "FrameDefaults": "Time constraints say we might not want to run this", + } def test_parameter_checks_poscontrol(self, param_prefix): self.wait_ready_to_arm() @@ -8983,6 +8985,56 @@ switch value''' if ex is not None: raise ex + def check_frame_defaults(self, model): + '''check each of the entries in VehicleInfo to see if they override + parameters they shouldn't''' + + defaults_filepath = self.model_defaults_filepath(self.vehicleinfo_key(), model) + # we start the model but without passing through the defaults: + self.customise_SITL_commandline( + [], + model=model, + defaults_filepath=[], + wipe=True) + failed = [] + for filepath in defaults_filepath: + parameters = mavparm.MAVParmDict() + if not os.path.exists(filepath): +# raise NotAchievedException("Bad parameter file referenced: %s" % str(filepath)) + failed.append("Bad parameter file referenced: %s" % str(filepath)) + parameters.load(filepath) + for (file_param_name, file_param_value) in parameters.items(): + try: + current_value = self.get_parameter(file_param_name, verbose=False) + except NotAchievedException as e: + failed.append("%s in (%s) but not in firmware" % + (filepath, file_param_name)) + continue + if current_value == parameters[file_param_name]: + failed.append("%s has same value (%f) in (%s) and in firmware" % + (filepath, current_value, file_param_name)) + continue + if len(failed): + self.progress("Frame (%s) failed:" % (model, )) + for i in failed: + self.progress(" %s" % i) + return False + return True + + def check_frames_defaults(self): + vinfo = vehicleinfo.VehicleInfo() + success = True + frames = vinfo.options[self.vehicleinfo_key()]["frames"] + for frame in frames: + if frames[frame].get("external_model", False): + continue + self.progress("Checking frame (%s)" % str(frame)) + if not self.check_frame_defaults(frame): + success = False + self.customise_SITL_commandline(["--unhide-groups"]) + if not success: + raise NotAchievedException("Defaults files validation failed") + def tests(self): return [ ("PIDTuning", @@ -9022,6 +9074,10 @@ switch value''' ("InitialMode", "Test initial mode switching", self.test_initial_mode), + + ("FrameDefaults", + "Test Frame defaults file", + self.check_frames_defaults), ] def post_tests_announcements(self): @@ -9056,6 +9112,7 @@ switch value''' return ret def mavfft_fttd(self, sensor_type, sensor_instance, since, until): + '''display fft for raw ACC data in current logfile''' '''object to store data about a single FFT plot''' diff --git a/Tools/autotest/pysim/vehicleinfo.py b/Tools/autotest/pysim/vehicleinfo.py index 99b6e8fe79..9a9b498251 100644 --- a/Tools/autotest/pysim/vehicleinfo.py +++ b/Tools/autotest/pysim/vehicleinfo.py @@ -106,16 +106,19 @@ class VehicleInfo(object): "IrisRos": { "waf_target": "bin/arducopter", "default_params_filename": "default_params/copter.parm", + "external_model": True, }, "gazebo-iris": { "waf_target": "bin/arducopter", "default_params_filename": ["default_params/copter.parm", "default_params/gazebo-iris.parm"], + "external_model": True, }, "airsim-copter": { "waf_target": "bin/arducopter", "default_params_filename": ["default_params/copter.parm", "default_params/airsim-quadX.parm"], + "external_model": True, }, # HELICOPTER "heli": { @@ -129,6 +132,7 @@ class VehicleInfo(object): }, "heli-compound": { "waf_target": "bin/arducopter-heli", + "default_params_filename": ["default_params/copter-heli.parm"], }, "singlecopter": { "waf_target": "bin/arducopter", @@ -142,9 +146,11 @@ class VehicleInfo(object): "scrimmage-copter" : { "waf_target": "bin/arducopter", "default_params_filename": "default_params/copter.parm", + "external_model": True, }, "calibration": { "extra_mavlink_cmds": "module load sitl_calibration;", + "default_params_filename": [], }, "Callisto": { "model": "octa-quad:@ROMFS/models/Callisto.json", @@ -270,14 +276,17 @@ class VehicleInfo(object): "waf_target": "bin/ardurover", "default_params_filename": ["default_params/rover.parm", "default_params/rover-skid.parm"], + "external_model": True, }, "airsim-rover": { "waf_target": "bin/ardurover", "default_params_filename": ["default_params/rover.parm", "default_params/airsim-rover.parm"], + "external_model": True, }, "calibration": { "extra_mavlink_cmds": "module load sitl_calibration;", + "default_params_filename": [], }, }, }, @@ -303,6 +312,7 @@ class VehicleInfo(object): "frames": { "tracker": { "waf_target": "bin/antennatracker", + "default_params_filename": [], }, }, }, diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index cd943849bd..13fba13250 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -567,11 +567,13 @@ class AutoTestQuadPlane(AutoTest): return "MANUAL" def disabled_tests(self): - return { + ret = super(AutoTestQuadPlane, self).disabled_tests() + ret.update({ "QAutoTune": "See https://github.com/ArduPilot/ardupilot/issues/10411", "FRSkyPassThrough": "Currently failing", "CPUFailsafe": "servo channel values not scaled like ArduPlane", - } + }) + return ret def test_pilot_yaw(self): self.takeoff(10, mode="QLOITER") diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index caa20ccfc9..004be13460 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -5640,10 +5640,12 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) return ret def disabled_tests(self): - return { + ret = super(AutoTestRover, self).disabled_tests() + ret.update({ "DriveMaxRCIN": "currently triggers Arithmetic Exception", "SlewRate": "got timing report failure on CI", - } + }) + return ret def rc_defaults(self): ret = super(AutoTestRover, self).rc_defaults()