autotest: add test that jamming simulator works

This commit is contained in:
Peter Barker 2024-08-24 17:14:25 +10:00 committed by Andrew Tridgell
parent 3c0c2bfa67
commit b89256bec4
1 changed files with 43 additions and 0 deletions

View File

@ -6803,6 +6803,48 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
}) })
self.assert_arm_failure("Duplicate Aux Switch Options") self.assert_arm_failure("Duplicate Aux Switch Options")
def JammingSimulation(self):
'''Test jamming simulation works'''
self.wait_ready_to_arm()
start_loc = self.assert_receive_message('GPS_RAW_INT')
self.set_parameter("SIM_GPS_JAM", 1)
class Requirement():
def __init__(self, field, min_value):
self.field = field
self.min_value = min_value
def met(self, m):
return getattr(m, self.field) > self.min_value
requirements = set([
Requirement('v_acc', 50000),
Requirement('h_acc', 50000),
Requirement('vel_acc', 1000),
Requirement('vel', 10000),
])
low_sats_seen = False
seen_bad_loc = False
tstart = self.get_sim_time()
while True:
if self.get_sim_time() - tstart > 120:
raise NotAchievedException("Did not see all jamming")
m = self.assert_receive_message('GPS_RAW_INT')
new_requirements = copy.copy(requirements)
for requirement in requirements:
if requirement.met(m):
new_requirements.remove(requirement)
requirements = new_requirements
if m.satellites_visible < 6:
low_sats_seen = True
here = self.assert_receive_message('GPS_RAW_INT')
if self.get_distance_int(start_loc, here) > 100:
seen_bad_loc = True
if len(requirements) == 0 and low_sats_seen and seen_bad_loc:
break
def tests(self): def tests(self):
'''return list of all tests''' '''return list of all tests'''
ret = super(AutoTestRover, self).tests() ret = super(AutoTestRover, self).tests()
@ -6898,6 +6940,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.OpticalFlow, self.OpticalFlow,
self.RCDuplicateOptionsExist, self.RCDuplicateOptionsExist,
self.ClearMission, self.ClearMission,
self.JammingSimulation,
]) ])
return ret return ret