Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Downstream #28200 #210

Merged
merged 3 commits into from
Sep 26, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 5 additions & 10 deletions libraries/AP_ICEngine/AP_ICEngine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
// @Param: OPTIONS
// @DisplayName: ICE options
// @Description: Options for ICE control. The Disable ignition in RC failsafe option will cause the ignition to be set off on any R/C failsafe. If Throttle while disarmed is set then throttle control will be allowed while disarmed for planes when in MANUAL mode. If disable while disarmed is set the engine will not start while the vehicle is disarmed unless overriden by the MAVLink DO_ENGINE_CONTROL command.
// @Bitmask: 0:Disable ignition in RC failsafe,1:Disable redline governor,2:Throttle while disarmed,3:Disable while disarmed
// @Bitmask: 0:Disable ignition in RC failsafe,1:Disable redline governor,2:Throttle control in MANUAL while disarmed with safety off,3:Disable while disarmed
AP_GROUPINFO("OPTIONS", 15, AP_ICEngine, options, 0),

// @Param: STARTCHN_MIN
Expand Down Expand Up @@ -356,7 +356,7 @@ void AP_ICEngine::update(void)
// reset initial height while disarmed
initial_height = -pos.z;
}
} else if (idle_percent <= 0 && !option_set(Options::THROTTLE_WHILE_DISARMED)) {
} else if (idle_percent <= 0 && !allow_throttle_while_disarmed()) {
// force ignition off when disarmed
state = ICE_OFF;
}
Expand Down Expand Up @@ -402,12 +402,7 @@ void AP_ICEngine::update(void)

case ICE_STARTING:
set_ignition(true);

if (hal.util->get_soft_armed() || allow_throttle_while_disarmed()) {
set_starter(true);
} else {
set_starter(false);
}
set_starter(true);

if (starter_start_time_ms == 0) {
starter_start_time_ms = now;
Expand Down Expand Up @@ -443,7 +438,7 @@ bool AP_ICEngine::throttle_override(float &percentage, const float base_throttle
idle_percent > percentage)
{
percentage = idle_percent;
if (option_set(Options::THROTTLE_WHILE_DISARMED) && !hal.util->get_soft_armed()) {
if (allow_throttle_while_disarmed() && !hal.util->get_soft_armed()) {
percentage = MAX(percentage, base_throttle);
}
return true;
Expand Down Expand Up @@ -484,7 +479,7 @@ bool AP_ICEngine::throttle_override(float &percentage, const float base_throttle
#endif // AP_RPM_ENABLED

// if THROTTLE_WHILE_DISARMED is set then we use the base_throttle, allowing the pilot to control throttle while disarmed
if (option_set(Options::THROTTLE_WHILE_DISARMED) && !hal.util->get_soft_armed() &&
if (allow_throttle_while_disarmed() && !hal.util->get_soft_armed() &&
base_throttle > percentage) {
percentage = base_throttle;
return true;
Expand Down
Loading