diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index bca8edb5d6..337c7ddb47 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -2406,6 +2406,11 @@ class AutoTestPlane(AutoTest): if not bad_value: raise NotAchievedException("uncompensated IMUs did not vary enough") + # the above tests change the internal persistent state of the + # vehicle in ways that autotest doesn't track (magically set + # parameters). So wipe the vehicle's eeprom: + self.reset_SITL_commandline() + def ekf_lane_switch(self): self.context_push()