autotest: Created test for unsuccessful takeoff level off

This commit is contained in:
George Zogopoulos 2024-11-22 11:36:22 +01:00 committed by Andrew Tridgell
parent 3ed6ada2e3
commit 768b2eabc4
2 changed files with 54 additions and 0 deletions

View File

@ -0,0 +1,13 @@
QGC WPL 110
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.390015 1
1 0 3 22 15.000000 0.000000 0.000000 0.000000 -35.361279 149.164230 50.000000 1
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361229 149.163025 80.000000 1
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364563 149.163773 80.000000 1
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364384 149.164795 80.000000 1
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361027 149.164093 80.000000 1
6 0 0 177 2.000000 3.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
7 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.362915 149.162613 60.000000 1
8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363136 149.162750 60.000000 1
9 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365467 149.164215 55.000000 1
10 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365009 149.165482 39.889999 1
11 0 3 21 0.000000 0.000000 0.000000 1.000000 -35.363041 149.165222 0.000000 1

View File

@ -4860,6 +4860,46 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
self.fly_home_land_and_disarm()
def TakeoffBadLevelOff(self):
'''Ensure that the takeoff can be completed under 0 pitch demand.'''
'''
When using no airspeed, the pitch level-off will eventually command 0
pitch demand. Ensure that the plane can climb the final 2m to deem the
takeoff complete.
'''
self.customise_SITL_commandline(
[],
model='plane-catapult',
defaults_filepath=self.model_defaults_filepath("plane")
)
self.set_parameters({
"ARSPD_USE": 0.0,
"PTCH_TRIM_DEG": -10.0,
"RTL_AUTOLAND": 2, # The mission contains a DO_LAND_START item.
"TKOFF_ALT": 50.0,
"TKOFF_DIST": 1000.0,
"TKOFF_THR_MAX": 75.0,
"TKOFF_THR_MINACC": 3.0,
})
self.load_mission("flaps_tkoff_50.txt")
self.change_mode('AUTO')
self.wait_ready_to_arm()
self.arm_vehicle()
# Throw the catapult.
self.set_servo(7, 2000)
# Wait until we've reached the takeoff altitude.
target_alt = 50
self.wait_altitude(target_alt-1, target_alt+1, relative=True, timeout=30)
self.delay_sim_time(5)
self.disarm_vehicle(force=True)
def DCMFallback(self):
'''Really annoy the EKF and force fallback'''
self.reboot_sitl()
@ -6452,6 +6492,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
self.TakeoffTakeoff4,
self.TakeoffGround,
self.TakeoffIdleThrottle,
self.TakeoffBadLevelOff,
self.ForcedDCM,
self.DCMFallback,
self.MAVFTP,