From 19bce3b1714d84388c3a3f13e79edb02a106a1e7 Mon Sep 17 00:00:00 2001 From: George Zogopoulos Date: Tue, 8 Oct 2024 21:10:02 +0200 Subject: [PATCH] autotest: added test for TKOFF_THR_IDLE --- Tools/autotest/arduplane.py | 29 +++++++++++++++++++++++++++++ 1 file changed, 29 insertions(+) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index bc0d157258..48334ab8d7 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -4831,6 +4831,34 @@ class AutoTestPlane(vehicle_test_suite.TestSuite): self.fly_home_land_and_disarm() + def TakeoffIdleThrottle(self): + '''Apply idle throttle before takeoff.''' + self.customise_SITL_commandline( + [], + model='plane-catapult', + defaults_filepath=self.model_defaults_filepath("plane") + ) + self.set_parameters({ + "TKOFF_THR_IDLE": 20.0, + "TKOFF_THR_MINSPD": 3.0, + }) + self.change_mode("TAKEOFF") + + self.wait_ready_to_arm() + self.arm_vehicle() + + # Ensure that the throttle rises to idle throttle. + expected_idle_throttle = 1000+10*self.get_parameter("TKOFF_THR_IDLE") + self.assert_servo_channel_range(3, expected_idle_throttle-10, expected_idle_throttle+10) + + # Launch the catapult + self.set_servo(6, 1000) + + self.delay_sim_time(5) + self.change_mode('RTL') + + self.fly_home_land_and_disarm() + def DCMFallback(self): '''Really annoy the EKF and force fallback''' self.reboot_sitl() @@ -6389,6 +6417,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite): self.TakeoffTakeoff3, self.TakeoffTakeoff4, self.TakeoffGround, + self.TakeoffIdleThrottle, self.ForcedDCM, self.DCMFallback, self.MAVFTP,