Prepare HAL device drivers to support Extended I2C Addresses

Update I2C addresses of HAL devices to type I2CAddress (to support extended address functions).
Cast I2CAddress variables in DIAG calls to (int).
Remove uses of max() function (not available on some platforms.
This commit is contained in:
Neil McKechnie 2023-02-07 14:55:14 +00:00
parent 13bd6ef9eb
commit d5a394d4e6
10 changed files with 68 additions and 61 deletions

View File

@ -59,14 +59,14 @@
**********************************************************************************************/
class ADS111x: public IODevice {
public:
static void create(VPIN firstVpin, int nPins, uint8_t i2cAddress) {
static void create(VPIN firstVpin, int nPins, I2CAddress i2cAddress) {
if (checkNoOverlap(firstVpin,nPins,i2cAddress)) new ADS111x(firstVpin, nPins, i2cAddress);
}
private:
ADS111x(VPIN firstVpin, int nPins, uint8_t i2cAddress) {
ADS111x(VPIN firstVpin, int nPins, I2CAddress i2cAddress) {
_firstVpin = firstVpin;
_nPins = min(nPins,4);
_i2cAddress = i2cAddress;
_nPins = (nPins > 4) ? 4 : nPins;
_I2CAddress = i2cAddress;
_currentPin = 0;
for (int8_t i=0; i<_nPins; i++)
_value[i] = -1;
@ -79,13 +79,13 @@ private:
// processing. So stick to fast mode (400kHz maximum).
I2CManager.setClock(400000);
// Initialise ADS device
if (I2CManager.exists(_i2cAddress)) {
if (I2CManager.exists(_I2CAddress)) {
_nextState = STATE_STARTSCAN;
#ifdef DIAG_IO
_display();
#endif
} else {
DIAG(F("ADS111x device not found, I2C:%x"), _i2cAddress);
DIAG(F("ADS111x device not found, I2C:%x"), (int)_I2CAddress);
_deviceState = DEVSTATE_FAILED;
}
}
@ -103,7 +103,7 @@ private:
_outBuffer[1] = 0xC0 + (_currentPin << 4); // Trigger single-shot, channel n
_outBuffer[2] = 0xA3; // 250 samples/sec, comparator off
// Write command, without waiting for completion.
I2CManager.write(_i2cAddress, _outBuffer, 3, &_i2crb);
I2CManager.write(_I2CAddress, _outBuffer, 3, &_i2crb);
delayUntil(currentMicros + scanInterval);
_nextState = STATE_STARTREAD;
@ -112,7 +112,7 @@ private:
case STATE_STARTREAD:
// Reading the pin value
_outBuffer[0] = 0x00; // Conversion register address
I2CManager.read(_i2cAddress, _inBuffer, 2, _outBuffer, 1, &_i2crb); // Read register
I2CManager.read(_I2CAddress, _inBuffer, 2, _outBuffer, 1, &_i2crb); // Read register
_nextState = STATE_GETVALUE;
break;
@ -131,7 +131,7 @@ private:
break;
}
} else { // error status
DIAG(F("ADS111x I2C:x%d Error:%d %S"), _i2cAddress, status, I2CManager.getErrorMessage(status));
DIAG(F("ADS111x I2C:x%d Error:%d %S"), (int)_I2CAddress, status, I2CManager.getErrorMessage(status));
_deviceState = DEVSTATE_FAILED;
}
}
@ -142,7 +142,7 @@ private:
}
void _display() override {
DIAG(F("ADS111x I2C:x%x Configured on Vpins:%d-%d %S"), _i2cAddress, _firstVpin, _firstVpin+_nPins-1,
DIAG(F("ADS111x I2C:x%x Configured on Vpins:%d-%d %S"), (int)_I2CAddress, _firstVpin, _firstVpin+_nPins-1,
_deviceState == DEVSTATE_FAILED ? F("OFFLINE") : F(""));
}
@ -159,7 +159,6 @@ private:
STATE_GETVALUE,
};
uint16_t _value[4];
uint8_t _i2cAddress;
uint8_t _outBuffer[3];
uint8_t _inBuffer[2];
uint8_t _currentPin; // ADC pin currently being scanned

View File

@ -54,13 +54,13 @@
*/
class EXIOExpander : public IODevice {
public:
static void create(VPIN vpin, int nPins, uint8_t i2cAddress, int numDigitalPins, int numAnaloguePins) {
static void create(VPIN vpin, int nPins, I2CAddress i2cAddress, int numDigitalPins, int numAnaloguePins) {
if (checkNoOverlap(vpin, nPins, i2cAddress)) new EXIOExpander(vpin, nPins, i2cAddress, numDigitalPins, numAnaloguePins);
}
private:
// Constructor
EXIOExpander(VPIN firstVpin, int nPins, uint8_t i2cAddress, int numDigitalPins, int numAnaloguePins) {
EXIOExpander(VPIN firstVpin, int nPins, I2CAddress i2cAddress, int numDigitalPins, int numAnaloguePins) {
_firstVpin = firstVpin;
_nPins = nPins;
_i2cAddress = i2cAddress;
@ -79,7 +79,7 @@ private:
// Send config, if EXIORDY returned, we're good, otherwise go offline
I2CManager.read(_i2cAddress, _digitalInBuffer, 1, _digitalOutBuffer, 3);
if (_digitalInBuffer[0] != EXIORDY) {
DIAG(F("ERROR configuring EX-IOExpander device, I2C:x%x"), _i2cAddress);
DIAG(F("ERROR configuring EX-IOExpander device, I2C:x%x"), (int)_i2cAddress);
_deviceState = DEVSTATE_FAILED;
return;
}
@ -91,12 +91,12 @@ private:
_minorVer = _versionBuffer[1];
_patchVer = _versionBuffer[2];
DIAG(F("EX-IOExpander device found, I2C:x%x, Version v%d.%d.%d"),
_i2cAddress, _versionBuffer[0], _versionBuffer[1], _versionBuffer[2]);
(int)_i2cAddress, _versionBuffer[0], _versionBuffer[1], _versionBuffer[2]);
#ifdef DIAG_IO
_display();
#endif
} else {
DIAG(F("EX-IOExpander device not found, I2C:x%x"), _i2cAddress);
DIAG(F("EX-IOExpander device not found, I2C:x%x"), (int)_i2cAddress);
_deviceState = DEVSTATE_FAILED;
}
}
@ -163,7 +163,7 @@ private:
_lastAnalogue = _firstVpin + _nPins - 1;
}
DIAG(F("EX-IOExpander I2C:x%x v%d.%d.%d: %d Digital Vpins %d-%d, %d Analogue Vpins %d-%d %S"),
_i2cAddress, _majorVer, _minorVer, _patchVer,
(int)_i2cAddress, _majorVer, _minorVer, _patchVer,
_numDigitalPins, _firstVpin, _firstVpin + _numDigitalPins - 1,
_numAnaloguePins, _firstAnalogue, _lastAnalogue,
_deviceState == DEVSTATE_FAILED ? F("OFFLINE") : F(""));

View File

@ -35,12 +35,12 @@
#include "I2CManager.h"
#include "DIAG.h"
void EXTurntable::create(VPIN firstVpin, int nPins, uint8_t I2CAddress) {
void EXTurntable::create(VPIN firstVpin, int nPins, I2CAddress I2CAddress) {
new EXTurntable(firstVpin, nPins, I2CAddress);
}
// Constructor
EXTurntable::EXTurntable(VPIN firstVpin, int nPins, uint8_t I2CAddress) {
EXTurntable::EXTurntable(VPIN firstVpin, int nPins, I2CAddress I2CAddress) {
_firstVpin = firstVpin;
_nPins = nPins;
_I2CAddress = I2CAddress;
@ -106,15 +106,15 @@ void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_
DIAG(F("EX-Turntable WriteAnalogue Vpin:%d Value:%d Activity:%d Duration:%d"),
vpin, value, activity, duration);
DIAG(F("I2CManager write I2C Address:%d stepsMSB:%d stepsLSB:%d activity:%d"),
_I2CAddress, stepsMSB, stepsLSB, activity);
(int)_I2CAddress, stepsMSB, stepsLSB, activity);
#endif
_stepperStatus = 1; // Tell the device driver Turntable-EX is busy
I2CManager.write(_I2CAddress, 3, stepsMSB, stepsLSB, activity);
I2CManager.write((int)_I2CAddress, 3, stepsMSB, stepsLSB, activity);
}
// Display Turnetable-EX device driver info.
void EXTurntable::_display() {
DIAG(F("EX-Turntable I2C:x%x Configured on Vpins:%d-%d %S"), _I2CAddress, (int)_firstVpin,
DIAG(F("EX-Turntable I2C:x%x Configured on Vpins:%d-%d %S"), (int)_I2CAddress, (int)_firstVpin,
(int)_firstVpin+_nPins-1, (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F(""));
}

View File

@ -49,13 +49,13 @@ protected:
// Data fields
// Allocate enough space for all input pins
T _portInputState;
T _portOutputState;
T _portMode;
T _portPullup;
T _portInUse;
// Interval between refreshes of each input port
static const int _portTickTime = 4000;
T _portInputState; // 1=high (inactive), 0=low (activated)
T _portOutputState; // 1 =high, 0=low
T _portMode; // 0=input, 1=output
T _portPullup; // 0=nopullup, 1=pullup
T _portInUse; // 0=not in use, 1=in use
// Target interval between refreshes of each input port
static const int _portTickTime = 4000; // 4ms
// Virtual functions for interfacing with I2C GPIO Device
virtual void _writeGpioPort() = 0;
@ -69,10 +69,6 @@ protected:
I2CRB requestBlock;
FSH *_deviceName;
#if defined(ARDUINO_ARCH_ESP32)
// workaround: Has somehow no min function for all types
static inline T min(T a, int b) { return a < b ? a : b; };
#endif
};
// Because class GPIOBase is a template, the implementation (below) must be contained within the same
@ -83,6 +79,7 @@ template <class T>
GPIOBase<T>::GPIOBase(FSH *deviceName, VPIN firstVpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin) :
IODevice(firstVpin, nPins)
{
if (_nPins > (int)sizeof(T)*8) _nPins = sizeof(T)*8; // Ensure nPins is consistent with the number of bits in T
_deviceName = deviceName;
_I2CAddress = i2cAddress;
_gpioInterruptPin = interruptPin;
@ -117,7 +114,6 @@ void GPIOBase<T>::_begin() {
// Configuration parameters for inputs:
// params[0]: enable pullup
// params[1]: invert input (optional)
template <class T>
bool GPIOBase<T>::_configure(VPIN vpin, ConfigTypeEnum configType, int paramCount, int params[]) {
if (configType != CONFIGURE_INPUT) return false;

View File

@ -32,7 +32,7 @@ public:
private:
// Constructor
MCP23008(VPIN firstVpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin=-1)
: GPIOBase<uint8_t>((FSH *)F("MCP23008"), firstVpin, min(nPins, (uint8_t)8), i2cAddress, interruptPin) {
: GPIOBase<uint8_t>((FSH *)F("MCP23008"), firstVpin, nPins, i2cAddress, interruptPin) {
requestBlock.setRequestParams(_I2CAddress, inputBuffer, sizeof(inputBuffer),
outputBuffer, sizeof(outputBuffer));
@ -60,7 +60,7 @@ private:
if (immediate) {
uint8_t buffer;
I2CManager.read(_I2CAddress, &buffer, 1, 1, REG_GPIO);
_portInputState = buffer;
_portInputState = buffer | _portMode;
} else {
// Queue new request
requestBlock.wait(); // Wait for preceding operation to complete
@ -71,7 +71,7 @@ private:
// 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 = inputBuffer[0];
_portInputState = inputBuffer[0] | _portMode;
else
_portInputState = 0xff;
}

View File

@ -30,13 +30,13 @@
class MCP23017 : public GPIOBase<uint16_t> {
public:
static void create(VPIN vpin, int nPins, I2CAddress i2cAddress, int interruptPin=-1) {
if (checkNoOverlap(vpin, nPins, i2cAddress)) new MCP23017(vpin, min(nPins,16), i2cAddress, interruptPin);
static void create(VPIN vpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin=-1) {
if (checkNoOverlap(vpin, nPins, i2cAddress)) new MCP23017(vpin, nPins, i2cAddress, interruptPin);
}
private:
// Constructor
MCP23017(VPIN vpin, int nPins, I2CAddress i2cAddress, int interruptPin=-1)
MCP23017(VPIN vpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin=-1)
: GPIOBase<uint16_t>((FSH *)F("MCP23017"), vpin, nPins, i2cAddress, interruptPin)
{
requestBlock.setRequestParams(_I2CAddress, inputBuffer, sizeof(inputBuffer),
@ -65,7 +65,7 @@ private:
if (immediate) {
uint8_t buffer[2];
I2CManager.read(_I2CAddress, buffer, 2, 1, REG_GPIOA);
_portInputState = ((uint16_t)buffer[1]<<8) | buffer[0];
_portInputState = ((uint16_t)buffer[1]<<8) | buffer[0] | _portMode;
} else {
// Queue new request
requestBlock.wait(); // Wait for preceding operation to complete
@ -76,7 +76,7 @@ private:
// 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];
_portInputState = (((uint16_t)inputBuffer[1]<<8) | inputBuffer[0]) | _portMode;
else
_portInputState = 0xffff;
}

View File

@ -75,7 +75,7 @@ bool PCA9685::_configure(VPIN vpin, ConfigTypeEnum configType, int paramCount, i
// Constructor
PCA9685::PCA9685(VPIN firstVpin, int nPins, I2CAddress i2cAddress) {
_firstVpin = firstVpin;
_nPins = min(nPins, 16);
_nPins = (nPins > 16) ? 16 : nPins;
_I2CAddress = i2cAddress;
// To save RAM, space for servo configuration is not allocated unless a pin is used.
// Initialise the pointers to NULL.
@ -272,5 +272,5 @@ static void writeRegister(byte address, byte reg, byte value) {
// The profile below is in the range 0-100% and should be combined with the desired limits
// of the servo set by _activePosition and _inactivePosition. The profile is symmetrical here,
// i.e. the bounce is the same on the down action as on the up action. First entry isn't used.
const byte FLASH PCA9685::_bounceProfile[30] =
const uint8_t FLASH PCA9685::_bounceProfile[30] =
{0,2,3,7,13,33,50,83,100,83,75,70,65,60,60,65,74,84,100,83,75,70,70,72,75,80,87,92,97,100};

View File

@ -49,14 +49,16 @@ public:
private:
PCF8574(VPIN firstVpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin=-1)
: GPIOBase<uint8_t>((FSH *)F("PCF8574"), firstVpin, min(nPins, (uint8_t)8), i2cAddress, interruptPin)
: GPIOBase<uint8_t>((FSH *)F("PCF8574"), firstVpin, nPins, i2cAddress, interruptPin)
{
requestBlock.setReadParams(_I2CAddress, inputBuffer, 1);
}
// The pin state is '1' if the pin is an input or if it is an output set to 1. Zero otherwise.
// The PCF8574 handles inputs by applying a weak pull-up when output is driven to '1'.
// The pin state is driven '1' if the pin is an input, or if it is an output set to 1.
// Unused pins are driven '0'.
void _writeGpioPort() override {
I2CManager.write(_I2CAddress, 1, _portOutputState | ~_portMode);
I2CManager.write(_I2CAddress, 1, (_portOutputState | ~_portMode) & _portInUse);
}
// The PCF8574 handles inputs by applying a weak pull-up when output is driven to '1'.
@ -64,9 +66,8 @@ private:
// and enable pull-up.
void _writePullups() override { }
// The pin state is '1' if the pin is an input or if it is an output set to 1. Zero otherwise.
void _writePortModes() override {
I2CManager.write(_I2CAddress, 1, _portOutputState | ~_portMode);
_writeGpioPort();
}
// In immediate mode, _readGpioPort reads the device GPIO port and updates _portInputState accordingly.
@ -76,7 +77,7 @@ private:
if (immediate) {
uint8_t buffer[1];
I2CManager.read(_I2CAddress, buffer, 1);
_portInputState = buffer[0];
_portInputState = buffer[0] | _portMode;
} else {
requestBlock.wait(); // Wait for preceding operation to complete
// Issue new request to read GPIO register
@ -87,7 +88,7 @@ private:
// 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 = inputBuffer[0];
_portInputState = inputBuffer[0] | _portMode;
else
_portInputState = 0xff;
}

View File

@ -45,7 +45,7 @@
class PCF8575 : public GPIOBase<uint16_t> {
public:
static void create(VPIN firstVpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin=-1) {
if (checkNoOverlap(firstVpin, nPins, i2cAddress)) new PCF8575(firstVpin, min(nPins,(uint8_t)16), i2cAddress, interruptPin);
if (checkNoOverlap(firstVpin, nPins, i2cAddress)) new PCF8575(firstVpin, nPins, i2cAddress, interruptPin);
}
private:
@ -55,9 +55,12 @@ private:
requestBlock.setReadParams(_I2CAddress, inputBuffer, sizeof(inputBuffer));
}
// The pin state is '1' if the pin is an input or if it is an output set to 1. Zero otherwise.
// The PCF8575 handles inputs by applying a weak pull-up when output is driven to '1'.
// The pin state is driven '1' if the pin is an input, or if it is an output set to 1.
// Unused pins are driven '0'.
void _writeGpioPort() override {
I2CManager.write(_I2CAddress, 2, _portOutputState | ~_portMode, (_portOutputState | ~_portMode)>>8);
uint16_t bits = (_portOutputState | ~_portMode) & _portInUse;
I2CManager.write(_I2CAddress, 2, bits, bits>>8);
}
// The PCF8575 handles inputs by applying a weak pull-up when output is driven to '1'.
@ -67,7 +70,7 @@ private:
// The pin state is '1' if the pin is an input or if it is an output set to 1. Zero otherwise.
void _writePortModes() override {
I2CManager.write(_I2CAddress, 2, _portOutputState | ~_portMode, (_portOutputState | ~_portMode)>>8);
_writeGpioPort();
}
// In immediate mode, _readGpioPort reads the device GPIO port and updates _portInputState accordingly.
@ -77,7 +80,7 @@ private:
if (immediate) {
uint8_t buffer[2];
I2CManager.read(_I2CAddress, buffer, 2);
_portInputState = ((uint16_t)buffer[1]<<8) | buffer[0];
_portInputState = (((uint16_t)buffer[1]<<8) | buffer[0]) | _portMode;
} else {
requestBlock.wait(); // Wait for preceding operation to complete
// Issue new request to read GPIO register
@ -88,7 +91,7 @@ private:
// 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];
_portInputState = (((uint16_t)inputBuffer[1]<<8) | inputBuffer[0]) | _portMode;
else
_portInputState = 0xffff;
}

View File

@ -136,14 +136,14 @@ private:
public:
static void create(VPIN firstVpin, int nPins, uint8_t i2cAddress, uint16_t onThreshold, uint16_t offThreshold, VPIN xshutPin = VPIN_NONE) {
static void create(VPIN firstVpin, int nPins, I2CAddress i2cAddress, uint16_t onThreshold, uint16_t offThreshold, VPIN xshutPin = VPIN_NONE) {
if (checkNoOverlap(firstVpin, nPins,i2cAddress)) new VL53L0X(firstVpin, nPins, i2cAddress, onThreshold, offThreshold, xshutPin);
}
protected:
VL53L0X(VPIN firstVpin, int nPins, uint8_t i2cAddress, uint16_t onThreshold, uint16_t offThreshold, VPIN xshutPin = VPIN_NONE) {
VL53L0X(VPIN firstVpin, int nPins, I2CAddress i2cAddress, uint16_t onThreshold, uint16_t offThreshold, VPIN xshutPin = VPIN_NONE) {
_firstVpin = firstVpin;
_nPins = min(nPins, 3);
_nPins = (nPins > 3) ? 3 : nPins;
_I2CAddress = i2cAddress;
_onThreshold = onThreshold;
_offThreshold = offThreshold;
@ -193,7 +193,15 @@ protected:
case STATE_CONFIGUREADDRESS:
// Then write the desired I2C address to the device, while this is the only
// module responding to the default address.
I2CManager.write(VL53L0X_I2C_DEFAULT_ADDRESS, 2, VL53L0X_REG_I2C_SLAVE_DEVICE_ADDRESS, _I2CAddress);
{
#if defined(I2C_EXTENDED_ADDRESS)
// Add subbus reference for desired address to the device default address.
I2CAddress defaultAddress = {_I2CAddress, VL53L0X_I2C_DEFAULT_ADDRESS};
I2CManager.write(defaultAddress, 2, VL53L0X_REG_I2C_SLAVE_DEVICE_ADDRESS, _I2CAddress.deviceAddress());
#else
I2CManager.write(VL53L0X_I2C_DEFAULT_ADDRESS, 2, VL53L0X_REG_I2C_SLAVE_DEVICE_ADDRESS, _I2CAddress);
#endif
}
_addressConfigInProgress = false;
_nextState = STATE_SKIP;
break;