1
0
mirror of https://github.com/DCC-EX/CommandStation-EX.git synced 2024-11-22 15:46:14 +01:00

Initial working IO_TCA8418 driver

This commit is contained in:
pmantoine 2024-10-24 13:19:07 +08:00
parent 1d18d5dea5
commit 535dcabcec
3 changed files with 369 additions and 137 deletions

View File

@ -1,5 +1,5 @@
/*
* © 2023, Paul M. Antoine
* © 2023-2024, Paul M. Antoine
* © 2021, Neil McKechnie. All rights reserved.
*
* This file is part of DCC-EX API
@ -21,163 +21,350 @@
#ifndef io_tca8418_h
#define io_tca8418_h
#include "IO_GPIOBase.h"
#include "IODevice.h"
#include "I2CManager.h"
#include "DIAG.h"
#include "FSH.h"
/////////////////////////////////////////////////////////////////////////////////////////////////////
/*
* IODevice subclass for TCA8418 80-key keypad encoder, which we'll treat as 64 of the possible
* 80 inputs for now, in an 8x8 matrix only, although the datasheet says:
* IODevice subclass for TCA8418 80-key keypad encoder, which we'll treat as 80 available VPINs where
* key down == 1 and key up == 0 by configuring just as an 8x10 keyboard matrix. Users can opt to use
* up to all 80 of the available VPINs for now, allowing memory to be saved if not all events are required.
*
* The datasheet says:
*
* The TCA8418 can be configured to support many different configurations of keypad setups.
* All 18 GPIOs for the rows and columns can be used to support up to 80 keys in an 8x10 key pad
* array. Another option is that all 18 GPIOs be used for GPIs to read 18 buttons which are
* not connected in an array. Any combination in between is also acceptable (for example, a
* 3x4 keypad matrix and using the remaining 11 GPIOs as a combination of inputs and outputs).
*
* With an 8x10 key event matrix, the events are numbered as such:
*
* C0 C1 C2 C3 C4 C5 C6 C7 C8 C9
* ========================================
* R0| 0 1 2 3 4 5 6 7 8 9
* R1| 10 11 12 13 14 15 16 17 18 19
* R2| 20 21 22 23 24 25 26 27 28 29
* R3| 30 31 32 33 34 35 36 37 38 39
* R4| 40 41 42 43 44 45 46 47 48 49
* R5| 50 51 52 53 54 55 56 57 58 59
* R6| 60 61 62 63 64 65 66 67 68 69
* R7| 70 71 72 73 74 75 76 77 78 79
*
* So if you start with VPIN 300, R0/C0 will be 300, and R7/C9 will be 379.
*
* HAL declaration for myAutomation.h is:
* HAL(TCA8418, firstVpin, numPins, I2CAddress, interruptPin)
*
* Where numPins can be 1-80, and interruptPin can be any spare Arduino pin.
*
* Configure using the following on the main I2C bus:
* HAL(TCA8418, 300, 80, 0x34)
*
* Use something like this on a multiplexor, and with up to 8 of the 8-way multiplexors you could have 64 different TCA8418 boards:
* HAL(TCA8418, 400, 80, {SubBus_1, 0x34})
*
* And if needing an Interrupt pin to speed up operations:
* HAL(TCA8418, 300, 80, 0x34, D21)
*
* Note that using an interrupt pin speeds up button press acquisition considerably (less than a millisecond vs 10-100),
* but even with interrupts enabled the code presently checks every 100ms in case the interrupt pin becomes disconnected.
* Use any available Arduino pin for interrupt monitoring.
*/
class TCA8418 : public GPIOBase<uint64_t> {
class TCA8418 : public IODevice {
public:
static void create(VPIN vpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin=-1) {
if (checkNoOverlap(vpin, nPins, i2cAddress))
// temporarily use the simple 18-pin GPIO mode - we'll switch to 8x8 matrix once this works
new TCA8418(vpin, (nPins = (nPins > 18) ? 18 : nPins), i2cAddress, interruptPin);
static void create(VPIN firstVpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin=-1) {
if (checkNoOverlap(firstVpin, nPins, i2cAddress))
new TCA8418(firstVpin, (nPins = (nPins > 80) ? 80 : nPins), i2cAddress, interruptPin);
}
private:
uint8_t* _digitalInputStates = NULL; // Array of pin states
uint8_t _digitalPinBytes = 0; // Number of bytes in pin state array
uint8_t _numKeyEvents = 0; // Number of outsanding key events waiting for us
unsigned long _lastEventRead = 0;
unsigned long _eventRefresh = 10000UL; // Delay refreshing events for 10ms
const unsigned long _eventRefreshSlow = 100000UL; // Delay refreshing events for 100ms
bool _gpioInterruptsEnabled = false;
uint8_t _inputBuffer[1];
uint8_t _commandBuffer[1];
I2CRB _i2crb;
enum {RDS_IDLE, RDS_EVENT, RDS_KEYCODE}; // Read operation states
uint8_t _readState = RDS_IDLE;
// Constructor
TCA8418(VPIN vpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin=-1)
: GPIOBase<uint64_t>((FSH *)F("TCA8418"), vpin, nPins, i2cAddress, interruptPin)
{
uint8_t receiveBuffer[1];
uint8_t commandBuffer[1];
uint8_t status;
commandBuffer[0] = REG_INT_STAT; // Check interrupt status
status = I2CManager.read(_I2CAddress, receiveBuffer, sizeof(receiveBuffer), commandBuffer, sizeof(commandBuffer));
if (status == I2C_STATUS_OK) {
DIAG(F("TCA8418 Interrupt status was: %x"), receiveBuffer[0]);
TCA8418(VPIN firstVpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin=-1) {
if (nPins > 0)
{
_firstVpin = firstVpin;
_nPins = nPins;
_I2CAddress = i2cAddress;
_gpioInterruptPin = interruptPin;
addDevice(this);
}
else
DIAG(F("TCA8418 Interrupt status failed to read!"));
// requestBlock.setRequestParams(_I2CAddress, inputBuffer, sizeof(inputBuffer),
// outputBuffer, sizeof(outputBuffer));
// outputBuffer[0] = REG_GPIOA;
}
void _writeGpioPort() override {
// I2CManager.write(_I2CAddress, 3, REG_GPIOA, _portOutputState, _portOutputState>>8);
}
void _writePullups() override {
// Set pullups only for in-use pins. This prevents pullup being set for a pin that
// is intended for use as an output but hasn't been written to yet.
uint32_t temp = _portPullup & _portInUse;
(void)temp; // Chris did this so he could see warnings that mattered
// I2CManager.write(_I2CAddress, 3, REG_GPPUA, temp, temp>>8);
}
void _writePortModes() override {
// Write 0 to each GPIO_DIRn for in-use pins that are inputs, 1 for outputs
uint64_t temp = _portMode & _portInUse;
DIAG(F("TCA8418 writing Port Mode: %x, to GPIO_DIRs"), temp);
DIAG(F("TCA8418 writing Port Mode: %x, to GPIO_DIR1"), (temp&0xFF));
I2CManager.write(_I2CAddress, 2, REG_GPIO_DIR1, (temp&0xFF));
DIAG(F("TCA8418 writing Port Mode: %x, to GPIO_DIR2"), ((temp&0xFF00)>>8));
I2CManager.write(_I2CAddress, 2, REG_GPIO_DIR2, ((temp&0xFF00)>>8));
DIAG(F("TCA8418 writing Port Mode: %x, to GPIO_DIR3"), (temp&0x30000)>>16);
I2CManager.write(_I2CAddress, 2, REG_GPIO_DIR3, ((temp&0x30000)>>16));
// Enable interrupt for in-use pins which are inputs (_portMode=0)
// TCA8418 has interrupt enables per pin, but must be configured for low->high
// or high->low... unlike the MCP23017
temp = ~_portMode & _portInUse;
DIAG(F("TCA8418 writing interrupt Port Mode: %x, to GPIO_INT_ENs"), temp);
DIAG(F("TCA8418 writing interrupt Port Mode: %x, to GPIO_INT_EN1"), (temp&0xFF));
I2CManager.write(_I2CAddress, 2, REG_GPIO_INT_EN1, (temp&0xFF));
DIAG(F("TCA8418 writing interrupt Port Mode: %x, to GPIO_INT_EN2"), ((temp&0xFF00)>>8));
I2CManager.write(_I2CAddress, 2, REG_GPIO_INT_EN2, ((temp&0xFF00)>>8));
DIAG(F("TCA8418 writing interrupt Port Mode: %x, to GPIO_INT_EN3"), (temp&0x30000)>>16);
I2CManager.write(_I2CAddress, 2, REG_GPIO_INT_EN3, ((temp&0x30000)>>16));
// I2CManager.write(_I2CAddress, 3, REG_INTCONA, 0x00, 0x00);
// I2CManager.write(_I2CAddress, 3, REG_GPINTENA, temp, temp>>8);
}
void _readGpioPort(bool immediate) override {
// if (immediate) {
// uint8_t buffer[2];
// I2CManager.read(_I2CAddress, buffer, 2, 1, REG_GPIOA);
// _portInputState = ((uint16_t)buffer[1]<<8) | buffer[0] | _portMode;
// } else {
// // Queue new request
// requestBlock.wait(); // Wait for preceding operation to complete
// // Issue new request to read GPIO register
// I2CManager.queueRequest(&requestBlock);
// }
}
// This function is invoked when an I/O operation on the requestBlock completes.
void _processCompletion(uint8_t status) override {
// if (status == I2C_STATUS_OK)
// _portInputState = (((uint16_t)inputBuffer[1]<<8) | inputBuffer[0]) | _portMode;
// else
// _portInputState = 0xffff;
}
void _setupDevice() override {
DIAG(F("TCA8418 setupDevice() called"));
// IOCON is set MIRROR=1, ODR=1 (open drain shared interrupt pin)
// I2CManager.write(_I2CAddress, 2, REG_IOCON, 0x44);
_writePortModes();
_writePullups();
_writeGpioPort();
void _begin() {
I2CManager.begin();
if (I2CManager.exists(_I2CAddress)) {
// Default all GPIO pins to INPUT
I2CManager.write(_I2CAddress, 2, REG_GPIO_DIR_1, 0x00);
I2CManager.write(_I2CAddress, 2, REG_GPIO_DIR_2, 0x00);
I2CManager.write(_I2CAddress, 2, REG_GPIO_DIR_3, 0x00);
// Remove all GPIO pins from events
I2CManager.write(_I2CAddress, 2, REG_GPI_EM_1, 0x00);
I2CManager.write(_I2CAddress, 2, REG_GPI_EM_2, 0x00);
I2CManager.write(_I2CAddress, 2, REG_GPI_EM_3, 0x00);
// Set all pins to FALLING interrupts
I2CManager.write(_I2CAddress, 2, REG_GPIO_INT_LVL_1, 0x00);
I2CManager.write(_I2CAddress, 2, REG_GPIO_INT_LVL_2, 0x00);
I2CManager.write(_I2CAddress, 2, REG_GPIO_INT_LVL_3, 0x00);
// Remove all GPIO pins from interrupts
I2CManager.write(_I2CAddress, 2, REG_GPIO_INT_EN_1, 0x00);
I2CManager.write(_I2CAddress, 2, REG_GPIO_INT_EN_2, 0x00);
I2CManager.write(_I2CAddress, 2, REG_GPIO_INT_EN_3, 0x00);
// Set up an 8 x 10 matrix by writing 0xFF to all the row and column configs
// Row config is maximum of 8, and in REG_KP_GPIO_1
I2CManager.write(_I2CAddress, 2, REG_KP_GPIO_1, 0xFF);
// Column config is maximum of 10, lower 8 bits in REG_KP_GPIO_2, upper in REG_KP_GPIO_3
// Set first 8 columns
I2CManager.write(_I2CAddress, 2, REG_KP_GPIO_2, 0xFF);
// Turn on cols 9/10
I2CManager.write(_I2CAddress, 2, REG_KP_GPIO_3, 0x03);
// // Set all pins to Enable Debounce
I2CManager.write(_I2CAddress, 2, REG_DEBOUNCE_DIS_1, 0x00);
I2CManager.write(_I2CAddress, 2, REG_DEBOUNCE_DIS_2, 0x00);
I2CManager.write(_I2CAddress, 2, REG_DEBOUNCE_DIS_3, 0x00);
// Let's assume an 8x10 matrix for now, and configure
_digitalPinBytes = (_nPins + 7) / 8;
if ((_digitalInputStates = (byte *)calloc(_digitalPinBytes, 1)) == NULL) {
DIAG(F("TCA8418 I2C: Unable to alloc %d bytes"), _digitalPinBytes);
return;
}
// Configure pin used for GPIO extender notification of change (if allocated)
// and configure TCA8418 to produce key event interrupts
if (_gpioInterruptPin >= 0) {
DIAG(F("TCA8418 I2C: interrupt pin configured on %d"), _gpioInterruptPin);
_gpioInterruptsEnabled = true;
_eventRefresh = _eventRefreshSlow; // Switch to slower manual refreshes in case the INT pin isn't connected!
pinMode(_gpioInterruptPin, INPUT_PULLUP);
I2CManager.write(_I2CAddress, 2, REG_CFG, REG_CFG_KE_IEN);
// Clear any pending interrupts
I2CManager.write(_I2CAddress, 2, REG_INT_STAT, REG_STAT_K_INT);
}
#ifdef DIAG_IO
_display();
#endif
}
}
enum
int _read(VPIN vpin) override {
if (_deviceState == DEVSTATE_FAILED)
return 0;
int pin = vpin - _firstVpin;
bool result = _digitalInputStates[pin / 8] & (1 << (pin % 8));
return result;
}
// Main loop, collect both digital and analogue pin states continuously (faster sensor/input reads)
void _loop(unsigned long currentMicros) override {
if (_deviceState == DEVSTATE_FAILED) return; // If device failed, return
// Request block is used for key event reads from the TCA8418, which are performed
// on a cyclic basis.
if (_readState != RDS_IDLE) {
if (_i2crb.isBusy()) return; // If I2C operation still in progress, return
uint8_t status = _i2crb.status;
if (status == I2C_STATUS_OK) { // If device request ok, read input data
// First check if we have any key events waiting
if (_readState == RDS_EVENT) {
if ((_numKeyEvents = (_inputBuffer[0] & 0x0F)) != 0) {
// We could read each key event waiting in a synchronous loop, which may prove preferable
// but for now, schedule an async read of the first key event in the queue
_commandBuffer[0] = REG_KEY_EVENT_A;
I2CManager.read(_I2CAddress, _inputBuffer, 1, _commandBuffer, 1, &_i2crb); // non-blocking read
_readState = RDS_KEYCODE; // Shift to reading key events!
}
else // We found no key events waiting, return to IDLE
_readState = RDS_IDLE;
}
else {
// RDS_KEYCODE
uint8_t key = _inputBuffer[0] & 0x7F;
bool keyDown = _inputBuffer[0] & 0x80;
// Check for just keypad events
key--; // R0/C0 is key #1, so subtract 1 to create an array offset
// We only want to record key events we're configured for, as we have calloc'd an
// appropriately sized _digitalInputStates array!
if (key < _nPins) {
if (keyDown)
_digitalInputStates[key / 8] |= (1 << (key % 8));
else
_digitalInputStates[key / 8] &= ~(1 << (key % 8));
}
else
DIAG(F("TCA8418 I2C: key event %d discarded, outside Vpin range"), key);
_numKeyEvents--; // One less key event to get
if (_numKeyEvents != 0)
{
// DIAG(F("TCA8418 I2C: more keys in read event queue, # waiting is: %x"), _numKeyEvents);
// We could read each key event waiting in a synchronous loop, which may prove preferable
// but for now, schedule an async read of the first key event in the queue
_commandBuffer[0] = REG_KEY_EVENT_A;
I2CManager.read(_I2CAddress, _inputBuffer, 1, _commandBuffer, 1, &_i2crb); // non-blocking read
}
else {
// DIAG(F("TCA8418 I2C: no more keys in read event queue"));
// Clear any pending interrupts
I2CManager.write(_I2CAddress, 2, REG_INT_STAT, REG_STAT_K_INT);
_readState = RDS_IDLE; // Shift to IDLE
return;
}
}
} else
reportError(status, false); // report eror but don't go offline.
}
// If we're not doing anything now, check to see if we have an interrupt pin configured and it is low,
// or if our timer has elapsed and we should check anyway in case the interrupt pin is disconnected.
if (_readState == RDS_IDLE) {
if ((_gpioInterruptsEnabled && !digitalRead(_gpioInterruptPin)) ||
((currentMicros - _lastEventRead) > _eventRefresh))
{
_commandBuffer[0] = REG_KEY_LCK_EC;
I2CManager.read(_I2CAddress, _inputBuffer, 1, _commandBuffer, 1, &_i2crb); // non-blocking read
_lastEventRead = currentMicros;
_readState = RDS_EVENT; // Shift to looking for key events!
}
}
}
// Display device information and status
void _display() override {
DIAG(F("TCA8418 I2C:%s Vpins %u-%u%S"),
_I2CAddress.toString(),
_firstVpin, (_firstVpin+_nPins-1),
_deviceState == DEVSTATE_FAILED ? F(" OFFLINE") : F(""));
if (_gpioInterruptsEnabled)
DIAG(F("TCA8418 I2C:Interrupt on pin %d"), _gpioInterruptPin);
}
// Helper function for error handling
void reportError(uint8_t status, bool fail=true) {
DIAG(F("TCA8418 I2C:%s Error:%d (%S)"), _I2CAddress.toString(),
status, I2CManager.getErrorMessage(status));
if (fail)
_deviceState = DEVSTATE_FAILED;
}
enum tca8418_registers
{
REG_FIRST_RESERVED = 0x00,
REG_CFG = 0x01,
REG_INT_STAT = 0x02,
REG_KEY_LCK_EC = 0x03,
REG_KEY_EVENT_A = 0x04,
REG_KEY_EVENT_B = 0x05,
REG_KEY_EVENT_C = 0x06,
REG_KEY_EVENT_D = 0x07,
REG_KEY_EVENT_E = 0x08,
REG_KEY_EVENT_F = 0x09,
REG_KEY_EVENT_G = 0x0A,
REG_KEY_EVENT_H = 0x0B,
REG_KEY_EVENT_I = 0x0C,
REG_KEY_EVENT_J = 0x0D,
REG_KP_LCK_TIMER = 0x0E,
REG_UNLOCK1 = 0x0F,
REG_UNLOCK2 = 0x10,
REG_GPIO_INT_STAT1 = 0x11,
REG_GPIO_INT_STAT2 = 0x12,
REG_GPIO_INT_STAT3 = 0x13,
REG_GPIO_DAT_STAT1 = 0x14,
REG_GPIO_DAT_STAT2 = 0x15,
REG_GPIO_DAT_STAT3 = 0x16,
REG_GPIO_DAT_OUT1 = 0x17,
REG_GPIO_DAT_OUT2 = 0x18,
REG_GPIO_DAT_OUT3 = 0x19,
REG_GPIO_INT_EN1 = 0x1A,
REG_GPIO_INT_EN2 = 0x1B,
REG_GPIO_INT_EN3 = 0x1C,
REG_KP_GPIO1 = 0x1D,
REG_KP_GPIO2 = 0x1E,
REG_KP_GPIO3 = 0x1F,
REG_GPI_EM1 = 0x20,
REG_GPI_EM2 = 0x21,
REG_GPI_EM3 = 0x22,
REG_GPIO_DIR1 = 0x23,
REG_GPIO_DIR2 = 0x24,
REG_GPIO_DIR3 = 0x25,
REG_GPIO_INT_LVL1 = 0x26,
REG_GPIO_INT_LVL2 = 0x27,
REG_GPIO_INT_LVL3 = 0x28,
REG_DEBOUNCE_DIS1 = 0x29,
REG_DEBOUNCE_DIS2 = 0x2A,
REG_DEBOUNCE_DIS3 = 0x2B,
REG_GPIO_PULL1 = 0x2C,
REG_GPIO_PULL2 = 0x2D,
REG_GPIO_PULL3 = 0x2E,
REG_LAST_RESERVED = 0x2F,
// REG_RESERVED = 0x00
REG_CFG = 0x01, // Configuration register
REG_INT_STAT = 0x02, // Interrupt status
REG_KEY_LCK_EC = 0x03, // Key lock and event counter
REG_KEY_EVENT_A = 0x04, // Key event register A
REG_KEY_EVENT_B = 0x05, // Key event register B
REG_KEY_EVENT_C = 0x06, // Key event register C
REG_KEY_EVENT_D = 0x07, // Key event register D
REG_KEY_EVENT_E = 0x08, // Key event register E
REG_KEY_EVENT_F = 0x09, // Key event register F
REG_KEY_EVENT_G = 0x0A, // Key event register G
REG_KEY_EVENT_H = 0x0B, // Key event register H
REG_KEY_EVENT_I = 0x0C, // Key event register I
REG_KEY_EVENT_J = 0x0D, // Key event register J
REG_KP_LCK_TIMER = 0x0E, // Keypad lock1 to lock2 timer
REG_UNLOCK_1 = 0x0F, // Unlock register 1
REG_UNLOCK_2 = 0x10, // Unlock register 2
REG_GPIO_INT_STAT_1 = 0x11, // GPIO interrupt status 1
REG_GPIO_INT_STAT_2 = 0x12, // GPIO interrupt status 2
REG_GPIO_INT_STAT_3 = 0x13, // GPIO interrupt status 3
REG_GPIO_DAT_STAT_1 = 0x14, // GPIO data status 1
REG_GPIO_DAT_STAT_2 = 0x15, // GPIO data status 2
REG_GPIO_DAT_STAT_3 = 0x16, // GPIO data status 3
REG_GPIO_DAT_OUT_1 = 0x17, // GPIO data out 1
REG_GPIO_DAT_OUT_2 = 0x18, // GPIO data out 2
REG_GPIO_DAT_OUT_3 = 0x19, // GPIO data out 3
REG_GPIO_INT_EN_1 = 0x1A, // GPIO interrupt enable 1
REG_GPIO_INT_EN_2 = 0x1B, // GPIO interrupt enable 2
REG_GPIO_INT_EN_3 = 0x1C, // GPIO interrupt enable 3
REG_KP_GPIO_1 = 0x1D, // Keypad/GPIO select 1
REG_KP_GPIO_2 = 0x1E, // Keypad/GPIO select 2
REG_KP_GPIO_3 = 0x1F, // Keypad/GPIO select 3
REG_GPI_EM_1 = 0x20, // GPI event mode 1
REG_GPI_EM_2 = 0x21, // GPI event mode 2
REG_GPI_EM_3 = 0x22, // GPI event mode 3
REG_GPIO_DIR_1 = 0x23, // GPIO data direction 1
REG_GPIO_DIR_2 = 0x24, // GPIO data direction 2
REG_GPIO_DIR_3 = 0x25, // GPIO data direction 3
REG_GPIO_INT_LVL_1 = 0x26, // GPIO edge/level detect 1
REG_GPIO_INT_LVL_2 = 0x27, // GPIO edge/level detect 2
REG_GPIO_INT_LVL_3 = 0x28, // GPIO edge/level detect 3
REG_DEBOUNCE_DIS_1 = 0x29, // Debounce disable 1
REG_DEBOUNCE_DIS_2 = 0x2A, // Debounce disable 2
REG_DEBOUNCE_DIS_3 = 0x2B, // Debounce disable 3
REG_GPIO_PULL_1 = 0x2C, // GPIO pull-up disable 1
REG_GPIO_PULL_2 = 0x2D, // GPIO pull-up disable 2
REG_GPIO_PULL_3 = 0x2E, // GPIO pull-up disable 3
// REG_RESERVED = 0x2F
};
enum tca8418_config_reg_fields
{
// Config Register #1 fields
REG_CFG_AI = 0x80, // Auto-increment for read/write
REG_CFG_GPI_E_CGF = 0x40, // Event mode config
REG_CFG_OVR_FLOW_M = 0x20, // Overflow mode enable
REG_CFG_INT_CFG = 0x10, // Interrupt config
REG_CFG_OVR_FLOW_IEN = 0x08, // Overflow interrupt enable
REG_CFG_K_LCK_IEN = 0x04, // Keypad lock interrupt enable
REG_CFG_GPI_IEN = 0x02, // GPI interrupt enable
REG_CFG_KE_IEN = 0x01, // Key events interrupt enable
};
enum tca8418_int_status_fields
{
// Interrupt Status Register #2 fields
REG_STAT_CAD_INT = 0x10, // Ctrl-alt-del seq status
REG_STAT_OVR_FLOW_INT = 0x08, // Overflow interrupt status
REG_STAT_K_LCK_INT = 0x04, // Key lock interrupt status
REG_STAT_GPI_INT = 0x02, // GPI interrupt status
REG_STAT_K_INT = 0x01, // Key events interrupt status
};
enum tca8418_lock_ec_fields
{
// Key Lock Event Count Register #3
REG_LCK_EC_K_LCK_EN = 0x40, // Key lock enable
REG_LCK_EC_LCK_2 = 0x20, // Keypad lock status 2
REG_LCK_EC_LCK_1 = 0x10, // Keypad lock status 1
REG_LCK_EC_KLEC_3 = 0x08, // Key event count bit 3
REG_LCK_EC_KLEC_2 = 0x04, // Key event count bit 2
REG_LCK_EC_KLEC_1 = 0x02, // Key event count bit 1
REG_LCK_EC_KLEC_0 = 0x01, // Key event count bit 0
};
};

44
Release_Notes/TCA8418.md Normal file
View File

@ -0,0 +1,44 @@
## TCA8418 ##
The TCA8418 IC from Texas Instruments is a low cost and very capable GPIO and keyboard scanner. Used as a keyboard scanner, it has 8 rows of 10 columns of IO pins which allow encoding of up to 80 buttons. The IC is available on an Adafruit board with Qwiic I2C interconnect called the "Adafruit TCA8418 Keypad Matrix and GPIO Expander Breakout" and available here for the modest sum of $US6 or so: https://www.adafruit.com/product/4918
The great advantage of this IC is that the keyboard scanning is done continuously, and it has a 10-element event queue, so even if you don't get to the interrupt immediately, keypress and release events will be held for you. Since it's I2C its very easy to use with any DCC-EX command station.
The TCA8418 driver presently configures the IC in the full 8x10 keyboard scanning mode, and then maps each key down/key up event to the state of a single vpin for extremely easy use from within EX-RAIL and JMRI as each key looks like an individual sensor.
This is ideal for mimic panels where you may need a lot of buttons, but with this board you can use just 18 wires to handle as many as 80 buttons.
By adding a simple HAL statement to myAutomation.h it creates between 1 and 80 buttons it will report back.
`HAL(TCA8418, firstVpin, numPins, I2CAddress, interruptPin)`
For example:
`HAL(TCA8418, 300, 80, 0x34)`
Creates VPINs 300-379 which you can monitor with EX-RAIL, JMRI sensors etc.
With an 8x10 key event matrix, the events are numbered using the Rn row pins and Cn column pins as such:
C0 C1 C2 C3 C4 C5 C6 C7 C8 C9
========================================
R0| 0 1 2 3 4 5 6 7 8 9
R1| 10 11 12 13 14 15 16 17 18 19
R2| 20 21 22 23 24 25 26 27 28 29
R3| 30 31 32 33 34 35 36 37 38 39
R4| 40 41 42 43 44 45 46 47 48 49
R5| 50 51 52 53 54 55 56 57 58 59
R6| 60 61 62 63 64 65 66 67 68 69
R7| 70 71 72 73 74 75 76 77 78 79
So if you start with the first pin definition being VPIN 300, R0/C0 will be 300 + 0, and R7/C9 will be 300+79 or 379.
Use something like this on a multiplexor, and with up to 8 of the 8-way multiplexors you could have 64 different TCA8418 boards:
`HAL(TCA8418, 400, 80, {SubBus_1, 0x34})`
And if needing an Interrupt pin to speed up operations:
`HAL(TCA8418, 300, 80, 0x34, 21)`
Note that using an interrupt pin speeds up button press acquisition considerably (less than a millisecond vs 10-100), but even with interrupts enabled the code presently checks every 100ms in case the interrupt pin becomes disconnected. Use any available Arduino pin for interrupt monitoring.

View File

@ -3,7 +3,8 @@
#include "StringFormatter.h"
#define VERSION "5.2.85"
#define VERSION "5.2.86"
// 5.2.86 - IO_TCA8418 driver for keypad matrix input now fully functioning, including being able to use an interrupt pin
// 5.2.85 - IO_TM1638 driver, SEG7 Exrail macro and _s7 segment pattern generator.
// 5.2.84 - Fix TrackManager setDCCSignal and setPROGSignal for STM32 shadowing of PORTG/PORTH - this time it really is correct!
// 5.2.83 - Various STM32 related fixes for serial ports, I2C pullups now turned off, and shadowing of PORTG/PORTH for TrackManager now correct