autotest: fix mission-load dedupe issue

There are other ways we can receive Flight Plan received now, and
MAVProxy's statustext dedupe stuff was biting us
This commit is contained in:
Peter Barker 2019-10-15 12:09:03 +11:00 committed by Andrew Tridgell
parent 3d59d2d6c8
commit b019043dae
1 changed files with 6 additions and 0 deletions

View File

@ -3080,6 +3080,7 @@ class AutoTest(ABC):
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION) self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
if not self.is_sub() and not self.is_tracker(): if not self.is_sub() and not self.is_tracker():
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_RALLY) self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
self.last_wp_load = time.time()
return return
self.mav.mav.mission_count_send(target_system, self.mav.mav.mission_count_send(target_system,
@ -3101,6 +3102,10 @@ class AutoTest(ABC):
raise NotAchievedException("Expected MAV_MISSION_ACCEPTED got %s" % raise NotAchievedException("Expected MAV_MISSION_ACCEPTED got %s" %
(mavutil.mavlink.enums["MAV_MISSION_RESULT"][m.type].name,)) (mavutil.mavlink.enums["MAV_MISSION_RESULT"][m.type].name,))
if mission_type == mavutil.mavlink.MAV_MISSION_TYPE_MISSION:
self.last_wp_load = time.time()
def clear_fence_using_mavproxy(self, timeout=10): def clear_fence_using_mavproxy(self, timeout=10):
self.mavproxy.send("fence clear\n") self.mavproxy.send("fence clear\n")
tstart = self.get_sim_time_cached() tstart = self.get_sim_time_cached()
@ -3121,6 +3126,7 @@ class AutoTest(ABC):
num_wp = mavwp.MAVWPLoader().count() num_wp = mavwp.MAVWPLoader().count()
if num_wp != 0: if num_wp != 0:
raise NotAchievedException("Failed to clear mission") raise NotAchievedException("Failed to clear mission")
self.last_wp_load = time.time()
def test_sensor_config_error_loop(self): def test_sensor_config_error_loop(self):
'''test the sensor config error loop works and that parameter sets are persistent''' '''test the sensor config error loop works and that parameter sets are persistent'''