From dba76d2c8bc0d6d0f6aea84bddc5786de0bba484 Mon Sep 17 00:00:00 2001 From: Shashwat Ganesh Date: Sat, 25 Feb 2023 23:55:07 +0530 Subject: [PATCH] Tools: plane: test gcs failsafe: FBWA and Parachute --- .../GCSFailsafe/plane-parachute-mission.txt | 5 +++ Tools/autotest/arduplane.py | 33 ++++++++++++++++++- 2 files changed, 37 insertions(+), 1 deletion(-) create mode 100644 Tools/autotest/ArduPlane_Tests/GCSFailsafe/plane-parachute-mission.txt diff --git a/Tools/autotest/ArduPlane_Tests/GCSFailsafe/plane-parachute-mission.txt b/Tools/autotest/ArduPlane_Tests/GCSFailsafe/plane-parachute-mission.txt new file mode 100644 index 0000000000..ea2924c2cc --- /dev/null +++ b/Tools/autotest/ArduPlane_Tests/GCSFailsafe/plane-parachute-mission.txt @@ -0,0 +1,5 @@ +QGC WPL 110 +0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.362045 149.165878 584.280029 1 +1 0 3 22 0.000000 0.000000 0.000000 0.000000 -35.362125 149.165039 10.000000 1 +2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364845 149.163452 11.000000 1 +3 0 0 208 2.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1 diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 6a96099648..5d3d086ef7 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -1178,9 +1178,40 @@ class AutoTestPlane(AutoTest): self.delay_sim_time(5) self.wait_mode("RTL") self.set_heartbeat_rate(self.speedup) - self.fly_home_land_and_disarm() self.end_subtest("Completed RTL Failsafe test") + self.start_subtest("Test Failsafe: FBWA Glide") + self.set_parameter("RTL_AUTOLAND", 1) + self.change_mode("AUTO") + self.takeoff() + self.set_parameter("FS_GCS_ENABL", 1) + self.set_parameter("FS_LONG_ACTN", 2) + self.progress("Disconnecting GCS") + self.set_heartbeat_rate(0) + self.delay_sim_time(5) + self.wait_mode("FBWA") + self.set_heartbeat_rate(self.speedup) + self.end_subtest("Completed FBWA Failsafe test") + + self.start_subtest("Test Failsafe: Deploy Parachute") + self.load_mission("plane-parachute-mission.txt") + self.set_current_waypoint(1) + self.set_parameters({ + "CHUTE_ENABLED": 1, + "CHUTE_TYPE": 10, + "SERVO9_FUNCTION": 27, + "SIM_PARA_ENABLE": 1, + "SIM_PARA_PIN": 9, + }) + self.change_mode("AUTO") + self.set_parameter("FS_LONG_ACTN", 3) + self.progress("Disconnecting GCS") + self.set_heartbeat_rate(0) + self.wait_statustext("BANG", timeout=60) + self.set_heartbeat_rate(self.speedup) + self.disarm_vehicle(force=True) + self.reboot_sitl() + self.end_subtest("Completed Parachute Failsafe test") def TestGripperMission(self): '''Test Gripper mission items'''