From b93e1d471ff0015a981feae02359e30aa2b917f9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 23 Aug 2023 17:37:44 +1000 Subject: [PATCH] autotest: add test for Rover MAV_CMD_NAV_RETURN_TO_LAUNCH --- Tools/autotest/rover.py | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 9545d380a3..a5f76d1b4d 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -6358,6 +6358,28 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.disarm_vehicle() + def MAV_CMD_NAV_RETURN_TO_LAUNCH(self): + '''test MAV_CMD_NAV_RETURN_TO_LAUNCH mavlink command''' + self.change_mode('GUIDED') + self.wait_ready_to_arm() + self.arm_vehicle() + + here = self.mav.location() + target_loc = self.offset_location_ne(here, 2000, 0) + self.send_guided_mission_item(target_loc) + self.wait_distance_to_home(20, 100) + + self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH) + self.wait_mode('RTL') + + self.change_mode('GUIDED') + + self.run_cmd_int(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH) + self.wait_mode('RTL') + + self.wait_distance_to_home(0, 5, timeout=30) + self.disarm_vehicle() + def tests(self): '''return list of all tests''' ret = super(AutoTestRover, self).tests() @@ -6424,6 +6446,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.DepthFinder, self.ChangeModeByNumber, self.EStopAtBoot, + self.MAV_CMD_NAV_RETURN_TO_LAUNCH, self.StickMixingAuto, self.AutoDock, self.PrivateChannel,