diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index 7863037460..d7785a32e7 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -643,6 +643,10 @@ void AP_ICEngine::set_ignition(bool on) } #endif // AP_RELAY_ENABLED +#if AP_ICENGINE_TCA9554_STARTER_ENABLED + tca9554_starter.set_ignition(on); +#endif + } /* diff --git a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp index 35f96ca35d..f218b21f76 100644 --- a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp @@ -103,6 +103,9 @@ void AP_ICEngine_TCA9554::set_starter(bool on, AP_Int8 crank_direction) if (crank_direction) { value |= REVERSE; } + if (ignition_on) { + value |= FUEL_PUMP; + } TCA9554_set(value); } diff --git a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h index 8740245b75..a31b54663a 100644 --- a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h +++ b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h @@ -9,6 +9,7 @@ class AP_ICEngine_TCA9554 { public: + void set_ignition(bool on) { ignition_on = on; } void set_starter(bool on, AP_Int8 crank_direction); private: @@ -17,6 +18,7 @@ class AP_ICEngine_TCA9554 { uint8_t last_state; bool initialised; + bool ignition_on; bool TCA9554_init(); void TCA9554_set(uint8_t value);