Skip to content

Commit 957bd4a

Browse files
committed
AP_ICEngine: reinstate STARTCHN_MIN and use trigger structure PWM feild for aux funciton triggers
1 parent f2ce8c9 commit 957bd4a

File tree

2 files changed

+12
-5
lines changed

2 files changed

+12
-5
lines changed

libraries/AP_ICEngine/AP_ICEngine.cpp

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -161,8 +161,7 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
161161
// @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.
162162
// @User: Standard
163163
// @Range: 0 1300
164-
165-
// 16 was STARTCHN_MIN
164+
AP_GROUPINFO("STARTCHN_MIN", 16, AP_ICEngine, start_chan_min_pwm, 0),
166165

167166
#if AP_RPM_ENABLED
168167
// @Param: REDLINE_RPM
@@ -282,9 +281,14 @@ void AP_ICEngine::param_conversion()
282281
}
283282

284283
// Handle incoming aux function
285-
void AP_ICEngine::do_aux_function(const RC_Channel::AuxSwitchPos ch_flag)
284+
void AP_ICEngine::do_aux_function(const RC_Channel::AuxFuncTrigger &trigger)
286285
{
287-
aux_pos = ch_flag;
286+
// If triggered from RC apply start chan min
287+
if ((trigger.source == RC_Channel::AuxFuncTrigger::Source::RC) && (trigger.pwm < start_chan_min_pwm)) {
288+
return;
289+
}
290+
291+
aux_pos = trigger.pos;
288292
}
289293

290294
/*

libraries/AP_ICEngine/AP_ICEngine.h

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,7 @@ class AP_ICEngine {
7171
bool allow_throttle_while_disarmed(void) const;
7272

7373
// Handle incoming aux function trigger
74-
void do_aux_function(const RC_Channel::AuxSwitchPos ch_flag);
74+
void do_aux_function(const RC_Channel::AuxFuncTrigger &trigger);
7575

7676
#if AP_RELAY_ENABLED
7777
// Needed for param conversion from relay numbers to functions
@@ -97,6 +97,9 @@ class AP_ICEngine {
9797
// enable library
9898
AP_Int8 enable;
9999

100+
// min pwm on start channel for engine stop
101+
AP_Int16 start_chan_min_pwm;
102+
100103
#if AP_RPM_ENABLED
101104
// which RPM instance to use
102105
AP_Int8 rpm_instance;

0 commit comments

Comments
 (0)