Skip to content

Commit

Permalink
autotest: correct Rover RangeFinder test
Browse files Browse the repository at this point in the history
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)
  • Loading branch information
peterbarker authored and robertlong13 committed Dec 28, 2024
1 parent ef27449 commit 626bc66
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions Tools/autotest/rover.py
Original file line number Diff line number Diff line change
Expand Up @@ -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())

Expand All @@ -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):
Expand Down

0 comments on commit 626bc66

Please sign in to comment.