Skip to content

Commit

Permalink
autotest: added test for TKOFF_THR_IDLE
Browse files Browse the repository at this point in the history
  • Loading branch information
Georacer authored and tridge committed Nov 13, 2024
1 parent db6a525 commit 19bce3b
Showing 1 changed file with 29 additions and 0 deletions.
29 changes: 29 additions & 0 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -4831,6 +4831,34 @@ def TakeoffGround(self):

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()
Expand Down Expand Up @@ -6389,6 +6417,7 @@ def tests1b(self):
self.TakeoffTakeoff3,
self.TakeoffTakeoff4,
self.TakeoffGround,
self.TakeoffIdleThrottle,
self.ForcedDCM,
self.DCMFallback,
self.MAVFTP,
Expand Down

0 comments on commit 19bce3b

Please sign in to comment.