From d4c24f2eb327335cd520e8754d501232289496ae Mon Sep 17 00:00:00 2001 From: Lokesh-Ramina Date: Tue, 19 Mar 2024 16:56:27 -0700 Subject: [PATCH] AP_ICEngine: Add CRANK_DIR for direction control of TCA9554 Engine Added a parameter CRAN_DIR where 0 if forward and 1 or greater is reverse direction for Engine Cranking. As all our Engine our forward direction that is our default state. SW-111 --- libraries/AP_ICEngine/AP_ICEngine.cpp | 9 ++++++++- libraries/AP_ICEngine/AP_ICEngine.h | 3 +++ libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp | 8 ++++++-- libraries/AP_ICEngine/AP_ICEngine_TCA9554.h | 7 ++++--- 4 files changed, 21 insertions(+), 6 deletions(-) diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index 110148d6da..59bd0bc314 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -163,6 +163,13 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = { // @Values: 0:None,1:Relay1,2:Relay2,3:Relay3,4:Relay4,5:Relay5,6:Relay6 AP_GROUPINFO("IGNITION_RLY", 18, AP_ICEngine, ignition_relay, 0), + // @Param: CRANK_DIR + // @DisplayName: Engine Cranking Direction for TCA9554 + // @Description: This will define which direction the engine is cranking for the TCA9554 starter control + // @User: Standard + // @Values: 0:Forward,1:Reverse + AP_GROUPINFO("CRANK_DIR", 19, AP_ICEngine, crank_direction, 0), + AP_GROUPEND }; @@ -583,7 +590,7 @@ void AP_ICEngine::set_starter(bool on) SRV_Channels::set_output_pwm(SRV_Channel::k_starter, on? pwm_starter_on : pwm_starter_off); #if AP_ICENGINE_TCA9554_STARTER_ENABLED - tca9554_starter.set_starter(on); + tca9554_starter.set_starter(on, crank_direction); #endif } diff --git a/libraries/AP_ICEngine/AP_ICEngine.h b/libraries/AP_ICEngine/AP_ICEngine.h index d72bf083b8..f26a5d5b33 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.h +++ b/libraries/AP_ICEngine/AP_ICEngine.h @@ -136,6 +136,9 @@ class AP_ICEngine { // relay number for ignition AP_Int8 ignition_relay; + // crank engine direction + AP_Int8 crank_direction; + // height when we enter ICE_START_HEIGHT_DELAY float initial_height; diff --git a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp index fddfa3363f..3d5a9d1b59 100644 --- a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp @@ -82,7 +82,7 @@ void AP_ICEngine_TCA9554::TCA9554_set(TCA9554_state_t value) } } -void AP_ICEngine_TCA9554::set_starter(bool on) +void AP_ICEngine_TCA9554::set_starter(bool on, AP_Int8 crank_direction) { if (!initialised) { initialised = TCA9554_init(); @@ -91,7 +91,11 @@ void AP_ICEngine_TCA9554::set_starter(bool on) return; } } - TCA9554_set(on? STARTER_ON : STARTER_OFF); + if (!crank_direction) { + TCA9554_set(on? STARTER_FORWARD : STARTER_OFF); + } else { + TCA9554_set(on? STARTER_REVERSE : STARTER_OFF); + } } #endif // AP_ICENGINE_TCA9554_STARTER_ENABLED diff --git a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h index 005a5ece6c..bb05257c7d 100644 --- a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h +++ b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h @@ -9,14 +9,15 @@ class AP_ICEngine_TCA9554 { public: - void set_starter(bool on); + void set_starter(bool on, AP_Int8 crank_direction); private: AP_HAL::OwnPtr dev_TCA9554; enum TCA9554_state_t { - STARTER_OFF = 0x30, // output register - 0011 0000 - STARTER_ON = 0x11, // output register - 0001 0001 - Forward direction + STARTER_OFF = 0x30, // output register - 0011 0000 + STARTER_FORWARD = 0x11, // output register - 0001 0001 - Forward direction + STARTER_REVERSE = 0x01, // output register - 0000 0001 - Reverse direction }; TCA9554_state_t last_state;