From 3dfd06cff2d882f4362535e4b1f2994a429bd5f1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 28 Sep 2023 17:15:08 +1000 Subject: [PATCH] Tools: add tests for MAV_CMD_DO_LAND_START for both int and long --- Tools/autotest/arduplane.py | 32 ++++++++++++++++++++++++++++++++ 1 file changed, 32 insertions(+) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index cc91fba550..642edfa46e 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -4952,6 +4952,37 @@ class AutoTestPlane(AutoTest): self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd) self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd_int) + def MAV_CMD_DO_LAND_START(self): + '''test MAV_CMD_DO_LAND_START as mavlink command''' + self.set_parameters({ + "RTL_AUTOLAND": 3, + }) + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30), + (mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM, 0, 0, 30), + self.create_MISSION_ITEM_INT( + mavutil.mavlink.MAV_CMD_DO_LAND_START, + ), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0), + ]) + + self.change_mode('AUTO') + self.wait_ready_to_arm() + + self.arm_vehicle() + + self.start_subtest("DO_LAND_START as COMMAND_LONG") + self.wait_current_waypoint(2) + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_LAND_START) + self.wait_current_waypoint(4) + + self.start_subtest("DO_LAND_START as COMMAND_INT") + self.set_current_waypoint(2) + self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_LAND_START) + self.wait_current_waypoint(4) + + self.fly_home_land_and_disarm() + def tests(self): '''return list of all tests''' ret = super(AutoTestPlane, self).tests() @@ -5049,6 +5080,7 @@ class AutoTestPlane(AutoTest): self.MAV_CMD_DO_AUTOTUNE_ENABLE, self.MAV_CMD_DO_GO_AROUND, self.MAV_CMD_DO_FLIGHTTERMINATION, + self.MAV_CMD_DO_LAND_START, ]) return ret