Skip to content

Commit

Permalink
AP_ICEngine: add max retrial of cranking
Browse files Browse the repository at this point in the history
Added Param MAX_RETRY which 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
  • Loading branch information
loki077 committed Aug 26, 2024
1 parent 616d74f commit d4738d8
Show file tree
Hide file tree
Showing 2 changed files with 20 additions and 2 deletions.
18 changes: 16 additions & 2 deletions libraries/AP_ICEngine/AP_ICEngine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,6 +167,12 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {

// 18 was IGNITION_RLY

// @Param: MAX_RETRY
// @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 254
AP_GROUPINFO("MAX_RETRY", 19, AP_ICEngine, max_crank_retry, 0),

AP_GROUPEND
};
Expand Down Expand Up @@ -340,8 +346,14 @@ void AP_ICEngine::update(void)
if (!AP::rpm()->get_rpm(rpm_instance-1, rpm_value) ||
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");
if (max_crank_retry == 0 || crank_retry_ct < max_crank_retry) {
state = ICE_START_DELAY;
crank_retry_ct++;
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Uncommanded engine stop");
} else {
state = ICE_OFF;
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Engine Max Crank Retry reached");
}
}
}
#endif
Expand All @@ -360,6 +372,8 @@ void AP_ICEngine::update(void)
// force ignition off when disarmed
state = ICE_OFF;
}
// reset the crank retry counter when disarmed
crank_retry_ct = 0;
}

#if AP_RPM_ENABLED
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_ICEngine/AP_ICEngine.h
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,10 @@ class AP_ICEngine {
AP_Int16 pwm_ignition_off;
AP_Int16 pwm_starter_on;
AP_Int16 pwm_starter_off;

// max crank retry
AP_Int8 max_crank_retry;
int8_t crank_retry_ct;

#if AP_RPM_ENABLED
// RPM above which engine is considered to be running
Expand Down

0 comments on commit d4738d8

Please sign in to comment.