mirror of https://github.com/ArduPilot/ardupilot
autotest: added test for TKOFF_THR_IDLE
This commit is contained in:
parent
db6a52581e
commit
19bce3b171
|
@ -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,
|
||||
|
|
Loading…
Reference in New Issue