Autotest: add EndMissionBehavior Test for rover

This commit is contained in:
Pierre Kancir 2021-01-26 17:39:53 +01:00 committed by Randy Mackay
parent db1c653cc6
commit c02dfd1214
2 changed files with 74 additions and 0 deletions

View File

@ -0,0 +1,3 @@
QGC WPL 110
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 0.000000 1
1 0 3 16 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 1

View File

@ -5441,6 +5441,73 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
break
self.disarm_vehicle()
def test_end_mission_behavior(self, timeout=60):
self.context_push()
ex = None
try:
self.load_mission("end-mission.txt")
self.wait_ready_to_arm()
self.arm_vehicle()
self.start_subtest("Test End Mission Behavior HOLD")
self.context_collect("STATUSTEXT")
self.change_mode("AUTO")
self.wait_text("Mission Complete", check_context=True, wallclock_timeout=2)
# On Hold we should just stop and don't update the navigation target anymore
tstart = self.get_sim_time()
while True:
if self.get_sim_time_cached() - tstart > 15:
raise AutoTestTimeoutException("Still getting POSITION_TARGET_GLOBAL_INT")
m = self.mav.recv_match(type="POSITION_TARGET_GLOBAL_INT",
blocking=True,
timeout=10)
if m is None:
self.progress("No POSITION_TARGET_GLOBAL_INT received, all good !")
break
self.context_clear_collection("STATUSTEXT")
self.change_mode("GUIDED")
self.context_collect("STATUSTEXT")
self.start_subtest("Test End Mission Behavior LOITER")
self.set_parameter("MIS_DONE_BEHAVE", 1)
self.change_mode("AUTO")
self.wait_text("Mission Complete", check_context=True, wallclock_timeout=2)
# On LOITER we should update the navigation target
tstart = self.get_sim_time()
while True:
if self.get_sim_time_cached() - tstart > 15:
raise AutoTestTimeoutException("Not getting POSITION_TARGET_GLOBAL_INT")
m = self.mav.recv_match(type="POSITION_TARGET_GLOBAL_INT",
blocking=True,
timeout=5)
if m is None:
self.progress("No POSITION_TARGET_GLOBAL_INT received")
continue
else:
if self.get_sim_time_cached() - tstart > 15:
self.progress("Got POSITION_TARGET_GLOBAL_INT, all good !")
break
self.change_mode("GUIDED")
self.start_subtest("Test End Mission Behavior ACRO")
self.set_parameter("MIS_DONE_BEHAVE", 2)
self.change_mode("AUTO")
self.wait_mode("ACRO")
self.start_subtest("Test End Mission Behavior MANUAL")
self.set_parameter("MIS_DONE_BEHAVE", 3)
self.change_mode("AUTO")
self.wait_mode("MANUAL")
self.disarm_vehicle()
except Exception as e:
self.progress("Caught exception: %s" %
self.get_exception_stacktrace(e))
ex = e
self.context_pop()
self.reboot_sitl()
if ex is not None:
raise ex
def tests(self):
'''return list of all tests'''
ret = super(AutoTestRover, self).tests()
@ -5647,6 +5714,10 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
"Test MAV proximity backend",
self.ap_proximity_mav),
("EndMissionBehavior",
"Test end mission behavior",
self.test_end_mission_behavior),
("LogUpload",
"Upload logs",
self.log_upload),