Skip to content

Commit

Permalink
AP_ICEngine_TCA9554: clean pin logic
Browse files Browse the repository at this point in the history
  • Loading branch information
robertlong13 committed Dec 10, 2024
1 parent d395812 commit 1ed7f3b
Show file tree
Hide file tree
Showing 2 changed files with 21 additions and 18 deletions.
30 changes: 19 additions & 11 deletions libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,21 +11,29 @@ extern const AP_HAL::HAL& hal;

/*
* TCA9554 output register mapping for PMB Rev E
* P0 = PMU_EN - PMU output ON/OFF (CN6 pin 2)
* P1 = ECU_EN - Unused (previously Engine Kill Switch)
* (Net labels in the schematic are out of date, but shown for reference)
* P0 = PMU_EN - Unused
* P1 = ECU_EN - Fuel Pump MOSFET (CN5 pin 3)
* P2 = I2C_P2 - Unused
* P3 = LED (active low)
* P4 = PMU_START - Crank Direction (CN6 pin 5)
* P5 = PMU_ARM - Crank Signal (CN6 pin 6)
* P5 = PMU_ARM - Crank Signal (CN6 pin 6) (active low)
* P6 = PMU_STAT_IN - Unused
* P7 = PMU_STAT - Unused
*/
enum PIN_MASK {
FUEL_PUMP = 1 << 1,
LED_OFF = 1 << 3,
REVERSE = 1 << 4,
STOP_CRANKING = 1 << 5,
};

#define TCA9554_I2C_BUS 1
#define TCA9554_I2C_ADDR 0x20
#define TCA9554_OUTPUT 0x01 // Output Port register address. Outgoing logic levels
#define TCA9554_OUT_DEFAULT 0x30 // 0011 0000
#define TCA9554_OUT_DEFAULT (LED_OFF | STOP_CRANKING)
#define TCA9554_CONF 0x03 // Configuration Port register address [0 = Output]
#define TCA9554_PINS 0xC2 // Set all used ports to outputs = 1100 0010
#define TCA9554_PINS (~(FUEL_PUMP | LED_OFF | REVERSE | STOP_CRANKING)) // Set all used ports to outputs

/*
initialise TCA9554
Expand Down Expand Up @@ -60,7 +68,7 @@ bool AP_ICEngine_TCA9554::TCA9554_init()
/*
set the state of the i2c controller
*/
void AP_ICEngine_TCA9554::TCA9554_set(TCA9554_state_t value)
void AP_ICEngine_TCA9554::TCA9554_set(uint8_t value)
{
const uint32_t now_ms = AP_HAL::millis();
if (now_ms - last_reg_check_ms > 100) {
Expand All @@ -76,7 +84,7 @@ void AP_ICEngine_TCA9554::TCA9554_set(TCA9554_state_t value)
if (value != last_state) {
WITH_SEMAPHORE(dev_TCA9554->get_semaphore());
// set outputs and status leds
if (dev_TCA9554->write_register(TCA9554_OUTPUT, (~(value<<2) & 0x0C) | value)) {
if (dev_TCA9554->write_register(TCA9554_OUTPUT, value)) {
last_state = value;
}
}
Expand All @@ -91,11 +99,11 @@ void AP_ICEngine_TCA9554::set_starter(bool on, AP_Int8 crank_direction)
return;
}
}
if (!crank_direction) {
TCA9554_set(on? STARTER_FORWARD : STARTER_OFF);
} else {
TCA9554_set(on? STARTER_REVERSE : STARTER_OFF);
uint8_t value = on ? 0 : STOP_CRANKING | LED_OFF;
if (crank_direction) {
value |= REVERSE;
}
TCA9554_set(value);
}

#endif // AP_ICENGINE_TCA9554_STARTER_ENABLED
9 changes: 2 additions & 7 deletions libraries/AP_ICEngine/AP_ICEngine_TCA9554.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,17 +14,12 @@ class AP_ICEngine_TCA9554 {
private:
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_TCA9554;

enum TCA9554_state_t {
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;
uint8_t last_state;

bool initialised;

bool TCA9554_init();
void TCA9554_set(TCA9554_state_t value);
void TCA9554_set(uint8_t value);
uint32_t last_reg_check_ms;
};

Expand Down

0 comments on commit 1ed7f3b

Please sign in to comment.