Skip to content

Commit

Permalink
AP_ICEngine: don't allow engine run with safety on
Browse files Browse the repository at this point in the history
Cherry-pick source:
 - AP_ICEngine: don't allow engine run with safety on : e070848
 - AP_EFI: fixed ignition while disarmed : 2956810

Cherry-pick was not sufficient, since the code has changed since 4.3.25. This code is tested after changes.
  • Loading branch information
Pradeep-Carbonix authored and loki077 committed Mar 22, 2024
1 parent f5e7850 commit cc708e0
Show file tree
Hide file tree
Showing 3 changed files with 32 additions and 2 deletions.
16 changes: 15 additions & 1 deletion libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,21 @@ void AP_EFI_Serial_Hirth::send_request()

// check for change or timeout for throttle value
if ((new_throttle != last_throttle) || (now - last_req_send_throttle_ms > 500)) {
request_was_sent = send_target_values(new_throttle);
bool allow_throttle = hal.util->get_soft_armed();
if (!allow_throttle) {
const auto *ice = AP::ice();
if (ice != nullptr) {
allow_throttle = ice->allow_throttle_disarmed();
}
}

if (allow_throttle) {
request_was_sent = send_target_values(new_throttle);
}
else {
request_was_sent = send_target_values(0);
}

last_throttle = new_throttle;
last_req_send_throttle_ms = now;
} else {
Expand Down
16 changes: 15 additions & 1 deletion libraries/AP_ICEngine/AP_ICEngine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -355,7 +355,12 @@ void AP_ICEngine::update(void)

case ICE_STARTING:
set_ignition(true);
set_starter(true);

if (allow_throttle_disarmed()) {
set_starter(true);
} else {
set_starter(false);
}

if (starter_start_time_ms == 0) {
starter_start_time_ms = now;
Expand Down Expand Up @@ -546,6 +551,15 @@ void AP_ICEngine::update_idle_governor(int8_t &min_throttle)
min_throttle = roundf(idle_governor_integrator);
}

/*
Allows throttle when disarmed and Safety Switch is not ON
*/
bool AP_ICEngine::allow_throttle_disarmed() const
{
return option_set(Options::THROTTLE_WHILE_DISARMED) &&
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED;
}

/*
set ignition state
*/
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_ICEngine/AP_ICEngine.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,8 @@ class AP_ICEngine {

static AP_ICEngine *get_singleton() { return _singleton; }

bool allow_throttle_disarmed() const;

private:
static AP_ICEngine *_singleton;

Expand Down

0 comments on commit cc708e0

Please sign in to comment.