From ad702370134144b0869f32850d0e36c5afcce1b5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 26 Sep 2023 16:25:02 +1000 Subject: [PATCH] Tools: handle MAV_CMD_DO_FLIGHTTERMINATION as both long and int --- Tools/autotest/arducopter.py | 18 ++++++++++++++++++ Tools/autotest/arduplane.py | 20 ++++++++++++++++++++ 2 files changed, 38 insertions(+) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 4559da65fa..c0a9a0638f 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -10264,6 +10264,23 @@ class AutoTestCopter(AutoTest): self.disarm_vehicle(force=True) self.reboot_sitl() + def _MAV_CMD_DO_FLIGHTTERMINATION(self, command): + self.set_parameters({ + "SYSID_MYGCS": self.mav.source_system, + "DISARM_DELAY": 0, + }) + self.wait_ready_to_arm() + self.arm_vehicle() + self.context_collect('STATUSTEXT') + command(mavutil.mavlink.MAV_CMD_DO_FLIGHTTERMINATION, p1=1) + self.wait_disarmed() + self.reboot_sitl() + + def MAV_CMD_DO_FLIGHTTERMINATION(self): + '''test MAV_CMD_DO_FLIGHTTERMINATION works on Copter''' + self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd) + self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd_int) + def tests2b(self): # this block currently around 9.5mins here '''return list of all tests''' ret = ([ @@ -10328,6 +10345,7 @@ class AutoTestCopter(AutoTest): self.RPLidarA2, self.SafetySwitch, self.BrakeZ, + self.MAV_CMD_DO_FLIGHTTERMINATION, ]) return ret diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 17a4c22fdb..c8d6023560 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -4926,6 +4926,25 @@ class AutoTestPlane(AutoTest): self._MAV_CMD_DO_GO_AROUND(self.run_cmd) self._MAV_CMD_DO_GO_AROUND(self.run_cmd_int) + def _MAV_CMD_DO_FLIGHTTERMINATION(self, command): + self.set_parameters({ + "AFS_ENABLE": 1, + "SYSID_MYGCS": self.mav.source_system, + "AFS_TERM_ACTION": 42, + }) + self.wait_ready_to_arm() + self.arm_vehicle() + self.context_collect('STATUSTEXT') + command(mavutil.mavlink.MAV_CMD_DO_FLIGHTTERMINATION, p1=1) + self.wait_disarmed() + self.wait_text('Terminating due to GCS request', check_context=True) + self.reboot_sitl() + + def MAV_CMD_DO_FLIGHTTERMINATION(self): + '''test MAV_CMD_DO_FLIGHTTERMINATION works on Plane''' + self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd) + self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd_int) + def tests(self): '''return list of all tests''' ret = super(AutoTestPlane, self).tests() @@ -5022,6 +5041,7 @@ class AutoTestPlane(AutoTest): self.MAV_CMD_DO_INVERTED_FLIGHT, self.MAV_CMD_DO_AUTOTUNE_ENABLE, self.MAV_CMD_DO_GO_AROUND, + self.MAV_CMD_DO_FLIGHTTERMINATION, ]) return ret