diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 268092550b..289795a840 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -3168,11 +3168,13 @@ class AutoTest(ABC): 0) def set_analog_rangefinder_parameters(self): - self.set_parameter("RNGFND1_TYPE", 1) - self.set_parameter("RNGFND1_MIN_CM", 0) - self.set_parameter("RNGFND1_MAX_CM", 4000) - self.set_parameter("RNGFND1_SCALING", 12.12) - self.set_parameter("RNGFND1_PIN", 0) + self.set_parameters({ + "RNGFND1_TYPE": 1, + "RNGFND1_MIN_CM": 0, + "RNGFND1_MAX_CM": 4000, + "RNGFND1_SCALING": 12.12, + "RNGFND1_PIN": 0, + }) def send_debug_trap(self, timeout=6000): self.progress("Sending trap to autopilot") @@ -5336,6 +5338,11 @@ Also, ignores heartbeats not from our target system''' self.disarm_vehicle(force=True) self.reboot_sitl() + def set_parameters(self, parameters): + '''set parameters from the supplied dict''' + for (name, value) in parameters.items(): + self.set_parameter(name, value) + def zero_mag_offset_parameters(self, compass_count=3): self.progress("Zeroing Mag OFS parameters") self.drain_mav()