From 957bd4afda2d0443565ad620f9bae769c5e89835 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 13 Dec 2024 21:25:34 +0000 Subject: [PATCH] AP_ICEngine: reinstate `STARTCHN_MIN` and use trigger structure PWM feild for aux funciton triggers --- libraries/AP_ICEngine/AP_ICEngine.cpp | 12 ++++++++---- libraries/AP_ICEngine/AP_ICEngine.h | 5 ++++- 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index b9cfdb1e98d268..5284d2c593f2e0 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -161,8 +161,7 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = { // @Description: This is a minimum PWM value for engine start channel for an engine stop to be commanded. Setting this value will avoid RC input glitches with low PWM values from causing an unwanted engine stop. A value of zero means any PWM above 800 and below 1300 triggers an engine stop. To stop the engine start channel must above the larger of this value and 800 and below 1300. // @User: Standard // @Range: 0 1300 - - // 16 was STARTCHN_MIN + AP_GROUPINFO("STARTCHN_MIN", 16, AP_ICEngine, start_chan_min_pwm, 0), #if AP_RPM_ENABLED // @Param: REDLINE_RPM @@ -282,9 +281,14 @@ void AP_ICEngine::param_conversion() } // Handle incoming aux function -void AP_ICEngine::do_aux_function(const RC_Channel::AuxSwitchPos ch_flag) +void AP_ICEngine::do_aux_function(const RC_Channel::AuxFuncTrigger &trigger) { - aux_pos = ch_flag; + // If triggered from RC apply start chan min + if ((trigger.source == RC_Channel::AuxFuncTrigger::Source::RC) && (trigger.pwm < start_chan_min_pwm)) { + return; + } + + aux_pos = trigger.pos; } /* diff --git a/libraries/AP_ICEngine/AP_ICEngine.h b/libraries/AP_ICEngine/AP_ICEngine.h index 7409fe6b1aa129..58cd11bd0ec5f4 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.h +++ b/libraries/AP_ICEngine/AP_ICEngine.h @@ -71,7 +71,7 @@ class AP_ICEngine { bool allow_throttle_while_disarmed(void) const; // Handle incoming aux function trigger - void do_aux_function(const RC_Channel::AuxSwitchPos ch_flag); + void do_aux_function(const RC_Channel::AuxFuncTrigger &trigger); #if AP_RELAY_ENABLED // Needed for param conversion from relay numbers to functions @@ -97,6 +97,9 @@ class AP_ICEngine { // enable library AP_Int8 enable; + // min pwm on start channel for engine stop + AP_Int16 start_chan_min_pwm; + #if AP_RPM_ENABLED // which RPM instance to use AP_Int8 rpm_instance;