Plane: add test for MAV_CMD_NAV_LOITER_TO_ALT

This commit is contained in:
Peter Barker 2024-09-26 15:19:02 +10:00 committed by Peter Barker
parent decf484702
commit beb4226740
1 changed files with 17 additions and 0 deletions

View File

@ -6206,6 +6206,22 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
'''ensure we don't die with a bad Roll channel defined'''
self.set_parameter("RCMAP_ROLL", 17)
def MAV_CMD_NAV_LOITER_TO_ALT(self):
'''test loiter to alt mission item'''
self.upload_simple_relhome_mission([
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
(mavutil.mavlink.MAV_CMD_NAV_LOITER_TO_ALT, 0, 0, 500),
(mavutil.mavlink.MAV_CMD_NAV_LOITER_TO_ALT, 0, 0, 100),
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0),
])
self.change_mode('AUTO')
self.wait_ready_to_arm()
self.arm_vehicle()
self.wait_altitude(450, 475, relative=True, timeout=600)
self.wait_altitude(75, 125, relative=True, timeout=600)
self.wait_current_waypoint(4)
self.fly_home_land_and_disarm()
def tests(self):
'''return list of all tests'''
ret = super(AutoTestPlane, self).tests()
@ -6258,6 +6274,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
self.AdvancedFailsafe,
self.LOITER,
self.MAV_CMD_NAV_LOITER_TURNS,
self.MAV_CMD_NAV_LOITER_TO_ALT,
self.DeepStall,
self.WatchdogHome,
self.LargeMissions,