From 4e8f3a7a3a8d5ab4920d190e4e73131b2e02b646 Mon Sep 17 00:00:00 2001 From: Dmitri Ranfft Date: Mon, 14 Jan 2019 15:17:01 +0100 Subject: [PATCH] Autotest: renamed requested RangeFinder parameters to account for the new changes. --- Tools/autotest/arducopter.py | 60 ++++++++++++++++++------------------ 1 file changed, 30 insertions(+), 30 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index b14dd05099..c07b736ed6 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -391,11 +391,11 @@ class AutoTestCopter(AutoTest): self.fetch_parameters() self.set_parameter("PLND_TYPE", 4) - self.set_parameter("RNGFND_TYPE", 1) - self.set_parameter("RNGFND_MIN_CM", 0) - self.set_parameter("RNGFND_MAX_CM", 4000) - self.set_parameter("RNGFND_PIN", 0) - self.set_parameter("RNGFND_SCALING", 12.12) + self.set_parameter("RNGFND1_TYPE", 1) + self.set_parameter("RNGFND1_MIN_CM", 0) + self.set_parameter("RNGFND1_MAX_CM", 4000) + self.set_parameter("RNGFND1_PIN", 0) + self.set_parameter("RNGFND1_SCALING", 12.12) self.reboot_sitl() @@ -1098,11 +1098,11 @@ class AutoTestCopter(AutoTest): self.set_parameter("SIM_FLOW_ENABLE", 1) self.set_parameter("FLOW_ENABLE", 1) - self.set_parameter("RNGFND_TYPE", 1) - self.set_parameter("RNGFND_MIN_CM", 0) - self.set_parameter("RNGFND_MAX_CM", 4000) - self.set_parameter("RNGFND_PIN", 0) - self.set_parameter("RNGFND_SCALING", 12.12, epsilon=0.01) + self.set_parameter("RNGFND1_TYPE", 1) + self.set_parameter("RNGFND1_MIN_CM", 0) + self.set_parameter("RNGFND1_MAX_CM", 4000) + self.set_parameter("RNGFND1_PIN", 0) + self.set_parameter("RNGFND1_SCALING", 12.12, epsilon=0.01) self.set_parameter("SIM_GPS_DISABLE", 1) self.set_parameter("SIM_TERRAIN", 0) @@ -1554,11 +1554,11 @@ class AutoTestCopter(AutoTest): raise NotAchievedException("Received unexpected RANGEFINDER msg") try: - self.set_parameter("RNGFND_TYPE", 1) - self.set_parameter("RNGFND_MIN_CM", 0) - self.set_parameter("RNGFND_MAX_CM", 4000) - self.set_parameter("RNGFND_PIN", 0) - self.set_parameter("RNGFND_SCALING", 12.12) + self.set_parameter("RNGFND1_TYPE", 1) + self.set_parameter("RNGFND1_MIN_CM", 0) + self.set_parameter("RNGFND1_MAX_CM", 4000) + self.set_parameter("RNGFND1_PIN", 0) + self.set_parameter("RNGFND1_SCALING", 12.12) self.set_parameter("RC9_OPTION", 10) # rangefinder self.set_rc(9, 2000) @@ -1679,11 +1679,11 @@ class AutoTestCopter(AutoTest): self.fetch_parameters() self.set_parameter("PLND_TYPE", 4) - self.set_parameter("RNGFND_TYPE", 1) - self.set_parameter("RNGFND_MIN_CM", 0) - self.set_parameter("RNGFND_MAX_CM", 4000) - self.set_parameter("RNGFND_PIN", 0) - self.set_parameter("RNGFND_SCALING", 12.12) + self.set_parameter("RNGFND1_TYPE", 1) + self.set_parameter("RNGFND1_MIN_CM", 0) + self.set_parameter("RNGFND1_MAX_CM", 4000) + self.set_parameter("RNGFND1_PIN", 0) + self.set_parameter("RNGFND1_SCALING", 12.12) self.reboot_sitl() @@ -2131,11 +2131,11 @@ class AutoTestCopter(AutoTest): ex = None try: - self.set_parameter("RNGFND_TYPE", 1) - self.set_parameter("RNGFND_MIN_CM", 0) - self.set_parameter("RNGFND_MAX_CM", 4000) - self.set_parameter("RNGFND_PIN", 0) - self.set_parameter("RNGFND_SCALING", 12.12) + self.set_parameter("RNGFND1_TYPE", 1) + self.set_parameter("RNGFND1_MIN_CM", 0) + self.set_parameter("RNGFND1_MAX_CM", 4000) + self.set_parameter("RNGFND1_PIN", 0) + self.set_parameter("RNGFND1_SCALING", 12.12) self.set_parameter("GRIP_ENABLE", 1) self.set_parameter("GRIP_TYPE", 1) self.set_parameter("SIM_GRPS_ENABLE", 1) @@ -2576,11 +2576,11 @@ class AutoTestCopter(AutoTest): # enable companion backend: self.set_parameter("PLND_TYPE", 1) - self.set_parameter("RNGFND_TYPE", 1) - self.set_parameter("RNGFND_MIN_CM", 0) - self.set_parameter("RNGFND_MAX_CM", 4000) - self.set_parameter("RNGFND_PIN", 0) - self.set_parameter("RNGFND_SCALING", 12.12) + self.set_parameter("RNGFND1_TYPE", 1) + self.set_parameter("RNGFND1_MIN_CM", 0) + self.set_parameter("RNGFND1_MAX_CM", 4000) + self.set_parameter("RNGFND1_PIN", 0) + self.set_parameter("RNGFND1_SCALING", 12.12) # set up a channel switch to enable precision loiter: self.set_parameter("RC7_OPTION", 39)