diff --git a/Tools/autotest/ArduPlane_Tests/AutoLandMode/autoland_mission.txt b/Tools/autotest/ArduPlane_Tests/AutoLandMode/autoland_mission.txt new file mode 100644 index 00000000000000..0f1a47ef515b07 --- /dev/null +++ b/Tools/autotest/ArduPlane_Tests/AutoLandMode/autoland_mission.txt @@ -0,0 +1,4 @@ +QGC WPL 110 +0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165238 584.089966 1 +1 0 3 22 15.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 1 +2 0 10 19 20.000000 0.000000 1.000000 0.000000 -35.342005 149.100266 100.000000 1 diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index a05ac4f33c907f..915522ee110477 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -4243,13 +4243,20 @@ def AutoLandMode(self): '''Test AUTOLAND mode''' self.set_parameters({ "AUTOLAND_DIR_OFF": 45, + "TERRAIN_FOLLOW": 1, + "AUTOLAND_CLIMB": 300, }) self.customise_SITL_commandline(["--home", "-35.362938,149.165085,585,173"]) self.context_collect('STATUSTEXT') - self.takeoff(alt=80, mode='TAKEOFF') + self.load_mission("autoland_mission.txt") + self.install_terrain_handlers_context() + self.change_mode("AUTO") + self.wait_ready_to_arm() + self.arm_vehicle() self.wait_text("Autoland direction", check_context=True) + self.wait_waypoint(2, 2, max_dist=100) self.change_mode(26) - self.wait_disarmed(120) + self.wait_disarmed(400) self.progress("Check the landed heading matches takeoff plus offset") self.wait_heading(218, accuracy=5, timeout=1) loc = mavutil.location(-35.362938, 149.165085, 585, 218) diff --git a/autoland_mission.txt b/autoland_mission.txt new file mode 100644 index 00000000000000..0f1a47ef515b07 --- /dev/null +++ b/autoland_mission.txt @@ -0,0 +1,4 @@ +QGC WPL 110 +0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165238 584.089966 1 +1 0 3 22 15.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 1 +2 0 10 19 20.000000 0.000000 1.000000 0.000000 -35.342005 149.100266 100.000000 1