From c898261698fb8a0742ce20abbc4d4f57bd0fb9a9 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 5 Jul 2022 16:31:29 +0900 Subject: [PATCH] Tools: autotest uses PRX1 parameters --- Tools/autotest/arducopter.py | 10 +++++----- Tools/autotest/rover.py | 4 ++-- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 514964bc21..af7fafe313 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -6126,7 +6126,7 @@ class AutoTestCopter(AutoTest): self.context_push() self.set_parameters({ "SERIAL5_PROTOCOL": 1, - "PRX_TYPE": 2, + "PRX1_TYPE": 2, "SIM_SPEEDUP": 8, # much GCS interaction }) self.reboot_sitl() @@ -6147,7 +6147,7 @@ class AutoTestCopter(AutoTest): self.load_fence("copter-avoidance-fence.txt") self.set_parameters({ "FENCE_ENABLE": 1, - "PRX_TYPE": 10, + "PRX1_TYPE": 10, "PRX_LOG_RAW": 1, "RC10_OPTION": 40, # proximity-enable }) @@ -6215,7 +6215,7 @@ class AutoTestCopter(AutoTest): home_string = "%s,%s,%s,%s" % (51.8752066, 14.6487840, 54.15, 0) for (name, prx_type, expected_distances) in sensors: self.start_subtest("Testing %s" % name) - self.set_parameter("PRX_TYPE", prx_type) + self.set_parameter("PRX1_TYPE", prx_type) self.customise_SITL_commandline([ "--uartF=sim:%s:" % name, "--home", home_string, @@ -6252,7 +6252,7 @@ class AutoTestCopter(AutoTest): ex = None try: self.set_parameters({ - "PRX_TYPE": 2, + "PRX1_TYPE": 2, "AVOID_ALT_MIN": 10, }) self.set_analog_rangefinder_parameters() @@ -6835,7 +6835,7 @@ class AutoTestCopter(AutoTest): ex = None try: self.set_parameter("SERIAL5_PROTOCOL", 1) - self.set_parameter("PRX_TYPE", 2) # mavlink + self.set_parameter("PRX1_TYPE", 2) # mavlink self.reboot_sitl() self.progress("Should be unhealthy while we don't send messages") diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 9912efad95..a5491025c0 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -571,7 +571,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.load_fence("rover-fence-ac-avoid.txt") self.set_parameters({ "FENCE_ENABLE": 0, - "PRX_TYPE": 10, + "PRX1_TYPE": 10, "RC10_OPTION": 40, # proximity-enable }) self.reboot_sitl() @@ -5335,7 +5335,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) ex = None try: self.set_parameters({ - "PRX_TYPE": 2, # AP_Proximity_MAV + "PRX1_TYPE": 2, # AP_Proximity_MAV "OA_TYPE": 2, # dijkstra "OA_DB_OUTPUT": 3, # send all items })