|
|
|
@ -5643,16 +5643,23 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
@@ -5643,16 +5643,23 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|
|
|
|
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") |
|
|
|
|
# race conditions here to do with get_sim_time() |
|
|
|
|
# swallowing heartbeats means we have to be a little |
|
|
|
|
# circuitous when testing here: |
|
|
|
|
self.change_mode("GUIDED") |
|
|
|
|
self.send_cmd_do_set_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") |
|
|
|
|
# race conditions here to do with get_sim_time() |
|
|
|
|
# swallowing heartbeats means we have to be a little |
|
|
|
|
# circuitous when testing here: |
|
|
|
|
self.change_mode("GUIDED") |
|
|
|
|
self.send_cmd_do_set_mode("AUTO") |
|
|
|
|
self.wait_mode("MANUAL") |
|
|
|
|
self.disarm_vehicle() |
|
|
|
|
except Exception as e: |
|
|
|
|