Skip to content

Commit

Permalink
Tools: autotest: test ICE max starter retry limit
Browse files Browse the repository at this point in the history
  • Loading branch information
robertlong13 committed Sep 17, 2024
1 parent 38e4df7 commit 751c759
Showing 1 changed file with 49 additions and 0 deletions.
49 changes: 49 additions & 0 deletions Tools/autotest/quadplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -1116,6 +1116,55 @@ def ICEngine(self):
self.change_mode('FBWA')
self.wait_servo_channel_value(3, 2000)

self.start_subtest("Testing automatic restart")
# Cause the engine to stop (actually just mess up the RPM sensor)
rpm_chan = self.get_parameter("ICE_RPM_CHAN")
self.set_parameter("ICE_RPM_CHAN", 120) # Set to a non-existent sensor
self.context_clear_collection("STATUSTEXT")
self.set_rc(rc_engine_start_chan, 2000)
self.wait_statustext("Uncommanded engine stop", check_context=True)
self.wait_statustext("Starting engine")
# Restore the engine
self.set_parameter("ICE_RPM_CHAN", rpm_chan)
# Make sure the engine continues to run for the next 30 seconds
try:
self.wait_statustext("Uncommanded engine stop", timeout=30)
# The desired result is for the wait_text raise AutoTestTimeoutException
raise NotAchievedException("Engine stopped unexpectedly")
except AutoTestTimeoutException:
pass
# Turn the engine back off
self.set_rc(rc_engine_start_chan, 1000)

self.start_subtest("Testing automatic starter attempt limit")
# Limit start attempts to 3
self.context_stop_collecting("STATUSTEXT")
max_tries = 3
self.set_parameter("ICE_STRT_MX_RTRY", max_tries)
# Cause the engine to stop (actually just mess up the RPM sensor)
rpm_chan = self.get_parameter("ICE_RPM_CHAN")
self.set_parameter("ICE_RPM_CHAN", 120) # Set to a non-existent sensor
# Try this test twice. After commanding an engine stop, the limit should reset
for i in range(2):
self.context_collect("STATUSTEXT")
self.set_rc(rc_engine_start_chan, 2000)
self.wait_statustext("Engine max crank attempts reached", check_context=True)
self.delay_sim_time(30) # wait for another 30 seconds to make sure the engine doesn't restart
messages = self.context_get().collections["STATUSTEXT"]
self.context_stop_collecting("STATUSTEXT")
# check for the exact number of starter attempts
attempts = 0
for m in messages:
if "Starting engine" == m.text:
attempts += 1
if attempts != max_tries:
raise NotAchievedException(f"Run {i+1}: Expected {max_tries} attempts, got {attempts}")
# Command an engine stop
self.context_collect("STATUSTEXT")
self.set_rc(rc_engine_start_chan, 1000)
self.wait_statustext("ignition:0", check_context=True)
self.context_stop_collecting("STATUSTEXT")

def ICEngineMission(self):
'''Test ICE Engine Mission support'''
rc_engine_start_chan = 11
Expand Down

0 comments on commit 751c759

Please sign in to comment.