From 999cf8532723eb894b8d6f32c887503852ebed8b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 29 Jul 2024 19:12:47 +1000 Subject: [PATCH] autotest: correct Rover RangeFinder test for reasons I can't fathom, defaulting the rangefinder state causes problems with the vehicle orientation in SITL - probably a state update fix somewhere. This test was kind of broken anyway - the RangeFinder was pointing latterally out from the vehicle, but is displayed forward of the vehicle (ther RANGEFINDER mavlink message conveys no orientation information) --- Tools/autotest/rover.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 6ab7b33566..239afa33f4 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -6103,10 +6103,10 @@ def FRAMStorage(self): def RangeFinder(self): '''Test RangeFinder''' # the following magic numbers correspond to the post locations in SITL - home_string = "%s,%s,%s,%s" % (51.8752066, 14.6487840, 54.15, 315) + home_string = "%s,%s,%s,%s" % (51.8752066, 14.6487840, 54.15, 231) rangefinder_params = { - "SIM_SONAR_ROT": 6, + "SIM_SONAR_ROT": 0, } rangefinder_params.update(self.analog_rangefinder_parameters()) @@ -6121,7 +6121,7 @@ def RangeFinder(self): if m.voltage == 0: raise NotAchievedException("Did not get non-zero voltage") want_range = 10 - if abs(m.distance - want_range) > 0.1: + if abs(m.distance - want_range) > 0.5: raise NotAchievedException("Expected %fm got %fm" % (want_range, m.distance)) def DepthFinder(self):