From b89256bec4e74645efe1b37c9146e56cdbbd057a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 24 Aug 2024 17:14:25 +1000 Subject: [PATCH] autotest: add test that jamming simulator works --- Tools/autotest/rover.py | 43 +++++++++++++++++++++++++++++++++++++++++ 1 file changed, 43 insertions(+) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 65041324a9..eb7c8dbf59 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -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") + 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): '''return list of all 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.RCDuplicateOptionsExist, self.ClearMission, + self.JammingSimulation, ]) return ret