Skip to content

Commit

Permalink
AP_ICEngine: don't run engine with safety engaged
Browse files Browse the repository at this point in the history
  • Loading branch information
robertlong13 committed Sep 25, 2024
1 parent c47205e commit 794a3b7
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions libraries/AP_ICEngine/AP_ICEngine.cpp
Original file line number Diff line number Diff line change
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 @@ -438,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 @@ -479,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

0 comments on commit 794a3b7

Please sign in to comment.