Skip to content

Commit

Permalink
AP_ICEngine: reinstate STARTCHN_MIN and use trigger structure PWM f…
Browse files Browse the repository at this point in the history
…eild for aux funciton triggers
  • Loading branch information
IamPete1 committed Dec 13, 2024
1 parent f2ce8c9 commit 957bd4a
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 5 deletions.
12 changes: 8 additions & 4 deletions libraries/AP_ICEngine/AP_ICEngine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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;
}

/*
Expand Down
5 changes: 4 additions & 1 deletion libraries/AP_ICEngine/AP_ICEngine.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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;
Expand Down

0 comments on commit 957bd4a

Please sign in to comment.