From 261307f87d8f03bbd158f812bad3f9e133bce6d7 Mon Sep 17 00:00:00 2001 From: Loki077 Date: Mon, 12 Aug 2024 11:17:51 +1000 Subject: [PATCH] AP_ICEngine: Direction control for cranking. Added a parameter _DIR where 0 if forward and 1 or greater is reverse direction for Engine Cranking. This is particular with Hirth Engine where both options are available. --- libraries/AP_ICEngine/AP_ICEngine.cpp | 5 ++++ libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp | 25 ++++++++++++++++++- libraries/AP_ICEngine/AP_ICEngine_TCA9554.h | 11 ++++++-- 3 files changed, 38 insertions(+), 3 deletions(-) diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index 67051949ab051..238855ba51c9c 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -167,6 +167,11 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = { // 18 was IGNITION_RLY +#if AP_ICENGINE_TCA9554_STARTER_ENABLED + // @Group: _TCA9554 + // @Path: AP_ICENGINE_TCA9554.cpp + AP_SUBGROUPINFO(tca9554_starter, "_TCA", 19, AP_ICEngine, AP_ICEngine_TCA9554), +#endif // AP_ICENGINE_TCA9554_STARTER_ENABLED AP_GROUPEND }; diff --git a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp index fddfa3363fc11..292614f5a95d0 100644 --- a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp @@ -6,6 +6,7 @@ #if AP_ICENGINE_TCA9554_STARTER_ENABLED #include "AP_ICEngine.h" +#include extern const AP_HAL::HAL& hal; @@ -27,6 +28,24 @@ extern const AP_HAL::HAL& hal; #define TCA9554_CONF 0x03 // Configuration Port register address [0 = Output] #define TCA9554_PINS 0xC2 // Set all used ports to outputs = 1100 0010 +const AP_Param::GroupInfo AP_ICEngine_TCA9554::var_info[] = { + + // @Param: _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("_DIR ", 1, AP_ICEngine_TCA9554, crank_direction, 0), + + AP_GROUPEND +}; + +// constructor +AP_ICEngine_TCA9554::AP_ICEngine_TCA9554() +{ + AP_Param::setup_object_defaults(this, var_info); +} + /* initialise TCA9554 */ @@ -91,7 +110,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 005a5ece6cfdf..97c58894cab72 100644 --- a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h +++ b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h @@ -9,14 +9,19 @@ class AP_ICEngine_TCA9554 { public: + AP_ICEngine_TCA9554(); + + static const struct AP_Param::GroupInfo var_info[]; + void set_starter(bool on); 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; @@ -25,6 +30,8 @@ class AP_ICEngine_TCA9554 { bool TCA9554_init(); void TCA9554_set(TCA9554_state_t value); uint32_t last_reg_check_ms; + // crank engine direction + AP_Int8 crank_direction; }; #endif // AP_ICENGINE_TCA9554_STARTER_ENABLED