Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Param for Max Retrial of Engine Cranking. #27926

Merged
merged 3 commits into from
Sep 27, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
47 changes: 47 additions & 0 deletions Tools/autotest/quadplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -1116,6 +1116,53 @@ def ICEngine(self):
self.change_mode('FBWA')
self.wait_servo_channel_value(3, 2000)

self.start_subtest("Testing automatic restart")
# Limit start attempts to 4
max_tries = 4
self.set_parameter("ICE_STRT_MX_RTRY", max_tries)
# Make the engine unable to run (by messing 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.set_rc(rc_engine_start_chan, 2000)
self.wait_statustext("Uncommanded engine stop")
self.wait_statustext("Starting engine")
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

check_context, similarly elsewhere in here

Copy link
Collaborator

@robertlong13 robertlong13 Sep 25, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Have to be careful here. I don't want

Starting engine
Engine running
Uncommanded engine stop
... [never starts again]

to pass, but if I check context on these, that would pass. I need to enforce an order. I expect to see

Starting engine
Engine running
Uncommanded engine stop
Starting engine
Engine running
Uncommanded engine stop
[... and so on and so forth]

Copy link
Collaborator

@robertlong13 robertlong13 Sep 26, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looking at this again today, I think the test is good like it is currently; I got myself a little confused on the call.

# 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_statustext raise AutoTestTimeoutException
raise NotAchievedException("Engine stopped unexpectedly")
except AutoTestTimeoutException:
pass
self.context_stop_collecting("STATUSTEXT")

self.start_subtest("Testing automatic starter attempt limit")
# Try this test twice.
# For the first run, since the engine has been running successfully in
# the previous test for 30 seconds, the limit should reset. For the
# second run, after commanding an engine stop, the limit should reset.
for i in range(2):
self.context_collect("STATUSTEXT")
self.set_parameter("ICE_RPM_CHAN", 120) # Set to a non-existent sensor
self.set_rc(rc_engine_start_chan, 2000)
self.wait_statustext("Engine max crank attempts reached", check_context=True, timeout=30)
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
32 changes: 29 additions & 3 deletions libraries/AP_ICEngine/AP_ICEngine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -181,6 +181,13 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
// This allows one time conversion while allowing user to flash between versions with and without converted params
AP_GROUPINFO_FLAGS("FMT_VER", 19, AP_ICEngine, param_format_version, 0, AP_PARAM_FLAG_HIDDEN),

// @Param: STRT_MX_RTRY
// @DisplayName: Maximum number of retries
// @Description: If set 0 then there is no limit to retrials. If set to a value greater than 0 then the engine will retry starting the engine this many times before giving up.
// @User: Standard
// @Range: 0 127
AP_GROUPINFO("STRT_MX_RTRY", 20, AP_ICEngine, max_crank_retry, 0),

AP_GROUPEND
};

Expand Down Expand Up @@ -379,6 +386,10 @@ void AP_ICEngine::update(void)
if (should_run) {
state = ICE_START_DELAY;
}
crank_retry_ct = 0;
// clear the last uncommanded stop time, we only care about tracking
// the last one since the engine was started
last_uncommanded_stop_ms = 0;
break;

case ICE_START_HEIGHT_DELAY: {
Expand All @@ -402,8 +413,16 @@ void AP_ICEngine::update(void)
if (!should_run) {
state = ICE_OFF;
} else if (now - starter_last_run_ms >= starter_delay*1000) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Starting engine");
state = ICE_STARTING;
// check if we should retry starting the engine
if (max_crank_retry <= 0 || crank_retry_ct < max_crank_retry) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Starting engine");
state = ICE_STARTING;
crank_retry_ct++;
loki077 marked this conversation as resolved.
Show resolved Hide resolved
loki077 marked this conversation as resolved.
Show resolved Hide resolved
} else {
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Engine max crank attempts reached");
// Mark the last run now so we don't send this message every loop
starter_last_run_ms = now;
loki077 marked this conversation as resolved.
Show resolved Hide resolved
}
}
break;

Expand All @@ -429,7 +448,14 @@ void AP_ICEngine::update(void)
rpm_value < rpm_threshold) {
// engine has stopped when it should be running
state = ICE_START_DELAY;
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Uncommanded engine stop");
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Uncommanded engine stop");
if (last_uncommanded_stop_ms != 0 &&
now - last_uncommanded_stop_ms > 3*(starter_time + starter_delay)*1000) {
// if it has been a long enough time since the last uncommanded stop
// (3 times the time between start attempts) then reset the retry count
crank_retry_ct = 0;
}
last_uncommanded_stop_ms = now;
}
}
#endif
Expand Down
7 changes: 7 additions & 0 deletions libraries/AP_ICEngine/AP_ICEngine.h
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,10 @@ class AP_ICEngine {
// delay between start attempts (seconds)
AP_Float starter_delay;

// max crank retry
AP_Int8 max_crank_retry;
int8_t crank_retry_ct;
loki077 marked this conversation as resolved.
Show resolved Hide resolved

#if AP_RPM_ENABLED
// RPM above which engine is considered to be running
AP_Int32 rpm_threshold;
Expand All @@ -118,6 +122,9 @@ class AP_ICEngine {
// time when we last ran the starter
uint32_t starter_last_run_ms;

// time when we last had an uncommanded engine stop
uint32_t last_uncommanded_stop_ms;

// throttle percentage for engine start
AP_Int8 start_percent;

Expand Down
Loading