From e2bb7b92b9b3604e0352233cabcb08a41ab713db Mon Sep 17 00:00:00 2001 From: Loki077 Date: Tue, 3 Sep 2024 15:59:27 +1000 Subject: [PATCH 1/3] AP_ICEngine: add max retrial of cranking Added Param MAX_RETRY which If set 0 or less, 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. --- libraries/AP_ICEngine/AP_ICEngine.cpp | 18 ++++++++++++++++-- libraries/AP_ICEngine/AP_ICEngine.h | 6 +++++- 2 files changed, 21 insertions(+), 3 deletions(-) diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index 59bd0bc314..5cb6dc0294 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -170,6 +170,13 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = { // @Values: 0:Forward,1:Reverse AP_GROUPINFO("CRANK_DIR", 19, AP_ICEngine, crank_direction, 0), + // @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 }; @@ -260,6 +267,7 @@ void AP_ICEngine::update(void) if (should_run) { state = ICE_START_DELAY; } + crank_retry_ct = 0; break; case ICE_START_HEIGHT_DELAY: { @@ -283,8 +291,14 @@ 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++; + } else { + gcs().send_text(MAV_SEVERITY_INFO, "Engine max crank attempts reached"); + } } break; diff --git a/libraries/AP_ICEngine/AP_ICEngine.h b/libraries/AP_ICEngine/AP_ICEngine.h index 4c5049c95b..86e05024d7 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.h +++ b/libraries/AP_ICEngine/AP_ICEngine.h @@ -103,7 +103,11 @@ 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; + // RPM above which engine is considered to be running AP_Int32 rpm_threshold; From 5ebb69e7e30fdf1b7899b3742c350a4f0b8fba33 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Mon, 16 Sep 2024 17:54:35 +1000 Subject: [PATCH 2/3] AP_ICEngine: rate-limit "max retry" error message --- libraries/AP_ICEngine/AP_ICEngine.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index 5cb6dc0294..357dada47d 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -298,6 +298,7 @@ void AP_ICEngine::update(void) crank_retry_ct++; } else { gcs().send_text(MAV_SEVERITY_INFO, "Engine max crank attempts reached"); + starter_last_run_ms = now; } } break; From 43ee8c95ce20eeee06a546428c22cc67f03906c7 Mon Sep 17 00:00:00 2001 From: Loki077 Date: Tue, 17 Sep 2024 13:02:22 +1000 Subject: [PATCH 3/3] Ottano defaults: added Max retry for cranking --- libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm index 6d40a6677e..d1140bf884 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm @@ -64,6 +64,7 @@ ICE_START_CHAN,6 ICE_START_DELAY,3 ICE_STARTCHN_MIN,950 ICE_STARTER_TIME,5 +ICE_STRT_MX_RTRY,5 INS_ACCEL_FILTER,10 INS_GYRO_FILTER,22 INS_HNTC2_ATT,60