From 548b871168cd876fe4341d24adebf0728eeaafb1 Mon Sep 17 00:00:00 2001 From: George Zogopoulos Date: Mon, 29 Jul 2024 21:55:39 +0200 Subject: [PATCH] autotest: Added airspeedless takeoff test with stock parameters --- Tools/autotest/arduplane.py | 41 +++++++++++++++++++++++++++++++++++++ 1 file changed, 41 insertions(+) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index aa7acb0bad..f427e410d4 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -4714,6 +4714,46 @@ class AutoTestPlane(vehicle_test_suite.TestSuite): self.fly_home_land_and_disarm() + def TakeoffTakeoff4(self): + '''Test the behaviour of a takeoff in TAKEOFF mode, pt4. + + This is the same as case #3, but with almost stock parameters and without a catapult. + + Conditions: + - ARSPD_USE=0 + ''' + + self.customise_SITL_commandline( + [], + model='plane-catapult', + defaults_filepath=self.model_defaults_filepath("plane") + ) + self.set_parameters({ + "ARSPD_USE": 0.0, + }) + self.change_mode("TAKEOFF") + + self.wait_ready_to_arm() + self.arm_vehicle() + + # Check whether we're at max throttle below TKOFF_LVL_ALT. + test_alt = self.get_parameter("TKOFF_LVL_ALT")-10 + self.wait_altitude(test_alt, test_alt+2, relative=True) + self.assert_servo_channel_value(3, 1000+10*(self.get_parameter("THR_MAX")), operator.le) + self.assert_servo_channel_value(3, 1000+10*(self.get_parameter("THR_MAX"))-10, operator.ge) + + # Check whether we're still at max throttle past TKOFF_LVL_ALT. + test_alt = self.get_parameter("TKOFF_LVL_ALT")+10 + self.wait_altitude(test_alt, test_alt+2, relative=True) + self.assert_servo_channel_value(3, 1000+10*(self.get_parameter("THR_MAX")), operator.le) + self.assert_servo_channel_value(3, 1000+10*(self.get_parameter("THR_MAX"))-10, operator.ge) + + # Wait for the takeoff to complete. + target_alt = self.get_parameter("TKOFF_ALT") + self.wait_altitude(target_alt-5, target_alt, relative=True) + + self.fly_home_land_and_disarm() + def DCMFallback(self): '''Really annoy the EKF and force fallback''' self.reboot_sitl() @@ -6060,6 +6100,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite): self.TakeoffTakeoff1, self.TakeoffTakeoff2, self.TakeoffTakeoff3, + self.TakeoffTakeoff4, self.ForcedDCM, self.DCMFallback, self.MAVFTP,