1
0
mirror of https://github.com/DCC-EX/CommandStation-EX.git synced 2025-04-21 12:31:19 +02:00

saving current

This commit is contained in:
travis-farmer 2024-12-15 12:18:52 -05:00
parent a11ebb3ed8
commit 2d1f4ca108
No known key found for this signature in database
GPG Key ID: 0BC296791D14CB35
2 changed files with 316 additions and 264 deletions

View File

@ -21,43 +21,39 @@
#include "IO_RSproto.h" #include "IO_RSproto.h"
#include "defines.h" #include "defines.h"
/************************************************************ static const byte PAYLOAD_FALSE = 0;
* RSproto implementation static const byte PAYLOAD_NORMAL = 1;
************************************************************/ static const byte PAYLOAD_STRING = 2;
// Constructor for RSproto taskBuffer::taskBuffer(Stream * myserial)
RSproto::RSproto(HardwareSerial &serial, unsigned long baud, uint16_t cycleTimeMS, int8_t txPin, int waitA) { {
_baud = baud; // constructor
_serialD = &serial; next=first;
_txPin = txPin; first=this;
_busNo = 0; serial = myserial;
}
_cycleTime = cycleTimeMS * 1000UL; // convert from milliseconds to microseconds. taskBuffer::~taskBuffer()
_waitA = waitA; {
if (_waitA < 3) _waitA = 3; // destructor
// Add device to HAL device chain
IODevice::addDevice(this);
// Add bus to RSproto chain.
_nextBus = _busList;
_busList = this;
} }
/* -= updateCrc =- /* -= updateCrc =-
// //
// add the CRC value from _calculateCrc (2 bytes) to the buffer. // add the CRC value from _calculateCrc (2 bytes) to the buffer.
*/ */
void RSproto::updateCrc(uint8_t *buf, uint16_t len) { void taskBuffer::updateCrc(uint8_t *crcBuf, uint8_t *buf, uint16_t len) {
if (sizeof(crcBuf) != 2) return;
uint16_t crc = _calculateCrc(buf, len); uint16_t crc = _calculateCrc(buf, len);
buf[len] = lowByte(crc); crcBuf[0] = lowByte(crc);
buf[len + 1] = highByte(crc); crcBuf[1] = highByte(crc);
} }
/* -= crcGood =- /* -= crcGood =-
// //
// return TRUE if CRC matched between buffer copy, and calculated. // return TRUE if CRC matched between buffer copy, and calculated.
*/ */
bool RSproto::crcGood(uint8_t *buf, uint16_t len) { bool taskBuffer::crcGood(uint8_t *buf, uint16_t len) {
uint16_t aduCrc = buf[len] | (buf[len + 1] << 8); uint16_t aduCrc = buf[len] | (buf[len + 1] << 8);
uint16_t calculatedCrc = _calculateCrc(buf, len); uint16_t calculatedCrc = _calculateCrc(buf, len);
#if defined(IO_DIAG) #if defined(IO_DIAG)
@ -71,7 +67,7 @@ bool RSproto::crcGood(uint8_t *buf, uint16_t len) {
// //
// use bitwise XOR to calculate CRC into a 16-bit byte // use bitwise XOR to calculate CRC into a 16-bit byte
*/ */
uint16_t RSproto::_calculateCrc(uint8_t *buf, uint16_t len) { uint16_t taskBuffer::_calculateCrc(uint8_t *buf, uint16_t len) {
uint16_t value = 0xFFFF; uint16_t value = 0xFFFF;
for (uint16_t i = 0; i < len; i++) { for (uint16_t i = 0; i < len; i++) {
value ^= (uint16_t)buf[i]; value ^= (uint16_t)buf[i];
@ -84,6 +80,209 @@ uint16_t RSproto::_calculateCrc(uint8_t *buf, uint16_t len) {
return value; return value;
} }
void taskBuffer::doCommand(uint8_t *commandBuffer, int commandSize) {
for (taskBuffer * t=first;t;t=t->next) t->doCommand2(nodeID,commandBuffer,commandSize);
}
void taskBuffer::doCommand2(uint8_t *commandBuffer, int commandSize) {
// process commands here to be sent
uint8_t crcBuffer[2];
updateCrc(crcBuffer, commandBuffer, commandSize);
//_serial->begin(115200);
//ArduinoPins::fastWriteDigital(bus->_txPin, HIGH);
digitalWrite(_txPin,HIGH);
unsigned long startMillis = millis();
serial->write(commandBuffer, 7);
serial->write(endChar, 1);
serial->flush();
digitalWrite(_txPin,LOW);
}
void taskBuffer::init(unsigned long baud, uint16_t cycleTimeMS, int8_t txPin) {
#ifdef RS485_SERIAL
RS485_SERIAL.begin(baud, SERIAL_8N1);
new taskBuffer(&RS485_SERIAL);
#endif
for (taskBuffer * t=first;t;t=t->next) t->_txPin = txPin;
pinMode(txPin, OUTPUT);
digitalWrite(txPin, LOW);
}
void taskBuffer::loop() {
for (taskBuffer * t=first;t;t=t->next) t->loop2();
}
void taskBuffer::loop2() {
// process received commands here
while (serial->available()) {
char ch = serial->read();
if (!inCommandPayload) {
if (ch == STARTBYTE) {
inCommandPayload = PAYLOAD_NORMAL;
bufferLength = 0;
buffer[0] = '\0';
}
} else { // if (inCommandPayload)
if (bufferLength < (COMMAND_BUFFER_SIZE-1))
buffer[bufferLength++] = ch;
if (inCommandPayload > PAYLOAD_NORMAL) {
if (inCommandPayload > 32 + 2) { // String way too long
ch = ENDBYTE; // we end this nonsense
inCommandPayload = PAYLOAD_NORMAL;
DIAG(F("Parse error: Unbalanced string"));
// fall through to ending parsing below
} else if (ch == '"') { // String end
inCommandPayload = PAYLOAD_NORMAL;
continue; // do not fall through
} else
inCommandPayload++;
}
if (inCommandPayload == PAYLOAD_NORMAL) {
if (ch == ENDBYTE) {
buffer[bufferLength] = '\0';
parseRx(buffer);
inCommandPayload = PAYLOAD_FALSE;
break;
} else if (ch == '"') {
inCommandPayload = PAYLOAD_STRING;
}
}
}
}
}
void taskBuffer::parseRx(uint8_t *buf) {
// pass on what we got
bool found = (buf[0] != STARTBYTE);
for (byte *b=buf; b[0] != '\0'; b++) {
if (found) {
parseOne(b);
found=false;
}
if (b[0] == STARTBYTE)
found = true;
}
}
void taskBuffer::parseOne(uint8_t *buf) {
// finaly, process the darn data
while (buf[0] == '<' || buf[0] == ' ')
buf++; // strip off any number of < or spaces
uint8_t toNode = buf[0];
if (toNode != 0) return; // not for master
uint8_t fromNode = buf[1];
uint8_t opcode = buf[2];
RSprotonode *node = RSprotonode::findNode(fromNode);
switch (opcode) {
case EXIOPINS:
{node->_numDigitalPins = buf[3];
node->_numAnaloguePins = buf[4];
// See if we already have suitable buffers assigned
if (node->_numDigitalPins>0) {
size_t digitalBytesNeeded = (node->_numDigitalPins + 7) / 8;
if (node->_digitalPinBytes < digitalBytesNeeded) {
// Not enough space, free any existing buffer and allocate a new one
if (node->_digitalPinBytes > 0) free(node->_digitalInputStates);
if ((node->_digitalInputStates = (byte*) calloc(digitalBytesNeeded, 1)) != NULL) {
node->_digitalPinBytes = digitalBytesNeeded;
} else {
DIAG(F("EX-IOExpander485 node:%d ERROR alloc %d bytes"), fromNode, digitalBytesNeeded);
//_deviceState = DEVSTATE_FAILED;
node->_digitalPinBytes = 0;
return;
}
}
}
if (node->_numAnaloguePins>0) {
size_t analogueBytesNeeded = node->_numAnaloguePins * 2;
if (node->_analoguePinBytes < analogueBytesNeeded) {
// Free any existing buffers and allocate new ones.
if (node->_analoguePinBytes > 0) {
free(node->_analogueInputBuffer);
free(node->_analogueInputStates);
free(node->_analoguePinMap);
}
node->_analogueInputStates = (uint8_t*) calloc(analogueBytesNeeded, 1);
node->_analogueInputBuffer = (uint8_t*) calloc(analogueBytesNeeded, 1);
node->_analoguePinMap = (uint8_t*) calloc(node->_numAnaloguePins, 1);
if (node->_analogueInputStates != NULL &&
node->_analogueInputBuffer != NULL &&
node->_analoguePinMap != NULL) {
node->_analoguePinBytes = analogueBytesNeeded;
} else {
DIAG(F("EX-IOExpander485 node:%d ERROR alloc analog pin bytes"), fromNode);
//_deviceState = DEVSTATE_FAILED;
node->_analoguePinBytes = 0;
return;
}
}
}
break;}
case EXIOPINS: {
for (int i = 3; i < node->_numAnaloguePins; i++) {
node->_analoguePinMap[i] = buf[i];
}
break;
}
case EXIOVER: {
node->_majorVer = buf[3];
node->_minorVer = buf[4];
node->_patchVer = buf[5];
break;
}
case EXIORDY: {
node->resFlag = 1;
break;
}
case EXIOERR: {
node->resFlag = -1;
break;
}
case EXIORDD: {
for (int i = 3; i < (node->_numDigitalPins+7)/8; i++) {
node->_digitalInputStates[i-3] = buf[i];
}
break;
}
case EXIORDAN: {
for (int i = 3; i < node->_numAnaloguePins*2; i++) {
node->_analogueInputBuffer[i-3] = buf[i];
}
break;
}
}
}
/************************************************************
* RSproto implementation
************************************************************/
// Constructor for RSproto
RSproto::RSproto(HardwareSerial &serial, unsigned long baud, uint16_t cycleTimeMS, int8_t txPin, int waitA) {
_baud = baud;
_serialD = &serial;
_txPin = txPin;
_busNo = 0;
task->init(baud, cycleTimeMS, txPin);
_cycleTime = cycleTimeMS * 1000UL; // convert from milliseconds to microseconds.
_waitA = waitA;
if (_waitA < 3) _waitA = 3;
// Add device to HAL device chain
IODevice::addDevice(this);
// Add bus to RSproto chain.
_nextBus = _busList;
_busList = this;
}
/* -= clearRxBuffer =- /* -= clearRxBuffer =-
// //
// BLOCKING method to empty stray data in RX buffer // BLOCKING method to empty stray data in RX buffer
@ -107,111 +306,15 @@ void RSproto::clearRxBuffer() {
void RSproto::_loop(unsigned long currentMicros) { void RSproto::_loop(unsigned long currentMicros) {
_currentMicros = currentMicros; _currentMicros = currentMicros;
if (_currentNode == NULL) { //if (_currentNode == NULL) {
_currentNode = _nodeListStart; // _currentNode = _nodeListStart;
} //}
if (_currentMicros - _cycleStartTime < _cycleTime) return; //if (_currentMicros - _cycleStartTime < _cycleTime) return;
_cycleStartTime = _currentMicros; //_cycleStartTime = _currentMicros;
if (_currentNode == NULL) return; //if (_currentNode == NULL) return;
task->loop();
bool flagOK = true;
#if defined(RSproto_STM_COMM)
ArduinoPins::fastWriteDigital(RSproto_STM_COMM,HIGH);
#endif
if (nodesInitialized()) {
memcpy(_currentNode->_analogueInputStates, _currentNode->_analogueInputBuffer, _currentNode->_analoguePinBytes); // Copy I2C input buffer to states
switch (_refreshOperation) {
case 0:
if (_currentNode->_numDigitalPins>0 && currentMicros - _lastDigitalRead > _digitalRefresh) { // Delay for digital read refresh
// Issue new read request for digital states. As the request is non-blocking, the buffer has to
// be allocated from heap (object state).
_currentNode->_readCommandBuffer[0] = _currentNode->getNodeID();
_currentNode->_readCommandBuffer[1] = EXIORDD;
updateCrc(_currentNode->_readCommandBuffer,sizeof(_currentNode->_readCommandBuffer)-2);
if (waitReceive == false) {
if (_txPin != VPIN_NONE) ArduinoPins::fastWriteDigital(_txPin, HIGH);
_serialD->write(_currentNode->_readCommandBuffer, sizeof(_currentNode->_readCommandBuffer));
_serialD->write(initBuffer, 1);
_serialD->flush();
if (_txPin != VPIN_NONE) ArduinoPins::fastWriteDigital(_txPin, LOW);
}
unsigned long startMillis = millis();
if (!_serialD->available()) {
if (waitReceive == true && _waitCounter > _waitA) {
flagOK = false;
} else waitReceive = true;
}
uint16_t len = 0;
unsigned long startMicros = micros();
bool rxDone = false;
byte tmpByte;
len = _serialD->readBytesUntil(0xFE,_currentNode->_digitalInputStates, 25);
if (!true/*crcGood(_currentNode->_digitalInputStates,sizeof(_currentNode->_digitalInputStates)-2)*/) {
DIAG(F("EX-IOExpander485 CRC error on node %d"), _currentNode->getNodeID());
flagOK = false;
}
if (!testAndStripMasterFlag(_currentNode->_digitalInputStates)) DIAG(F("Foreign RSproto Device! no master flag from node %d"),_currentNode->getNodeID());
if (!waitReceive) _refreshOperation++;
_lastDigitalRead = currentMicros;
_readState = RDS_DIGITAL;
}
break;
case 1:
if (_currentNode->_numAnaloguePins>0 && currentMicros - _lastAnalogueRead > _analogueRefresh) { // Delay for analogue read refresh
// Issue new read for analogue input states
_currentNode->_readCommandBuffer[0] = _currentNode->getNodeID();
_currentNode->_readCommandBuffer[1] = EXIORDAN;
updateCrc(_currentNode->_readCommandBuffer,sizeof(_currentNode->_readCommandBuffer)-2);
if (waitReceive == false) {
if (_txPin != VPIN_NONE) ArduinoPins::fastWriteDigital(_txPin, HIGH);
_serialD->write(_currentNode->_readCommandBuffer, sizeof(_currentNode->_readCommandBuffer));
_serialD->write(initBuffer, 1);
_serialD->flush();
if (_txPin != VPIN_NONE) ArduinoPins::fastWriteDigital(_txPin, LOW);
}
unsigned long startMillis = millis();
if (!_serialD->available()) {
if (waitReceive == true && _waitCounter > _waitA) {
flagOK = false;
} else waitReceive = true;
}
uint16_t len = 0;
unsigned long startMicros = micros();
bool rxDone = false;
byte tmpByte;
len = _serialD->readBytesUntil(0xFE,_currentNode->_analogueInputBuffer, 25);
if (!true/*crcGood(_currentNode->_digitalInputStates,sizeof(_currentNode->_digitalInputStates)-2)*/) {
DIAG(F("EX-IOExpander485 CRC error on node %d"), _currentNode->getNodeID());
flagOK = false;
}
if (!testAndStripMasterFlag(_currentNode->_digitalInputStates)) DIAG(F("Foreign RSproto Device! no master flag from node %d"),_currentNode->getNodeID());
if (!waitReceive) _refreshOperation = 0;
_lastAnalogueRead = currentMicros;
_readState = RDS_ANALOGUE;
}
break;
if(flagOK && !waitReceive) _currentNode = _currentNode->getNext();
}
}
#if defined(RSproto_STM_OK)
if (flagOK == true) {
ArduinoPins::fastWriteDigital(RSproto_STM_OK,HIGH);
} else {
ArduinoPins::fastWriteDigital(RSproto_STM_OK,LOW);
}
#endif
#if defined(RSproto_STM_FAIL)
if (flagOK == false) {
ArduinoPins::fastWriteDigital(RSproto_STM_FAIL,HIGH);
} else {
ArduinoPins::fastWriteDigital(RSproto_STM_FAIL,LOW);
}
#endif
#if defined(RSproto_STM_COMM)
ArduinoPins::fastWriteDigital(RSproto_STM_COMM,LOW);
#endif
} }
@ -232,8 +335,8 @@ RSprotonode::RSprotonode(VPIN firstVpin, int nPins, uint8_t nodeID) {
_nPins = nPins; _nPins = nPins;
_busNo = 0; _busNo = 0;
_nodeID = nodeID; _nodeID = nodeID;
bus = bus->findBus(0); //bus = bus->findBus(0);
_serial = bus->_serialD; //_serial = bus->_serialD;
if (_nodeID > 254) _nodeID = 254; if (_nodeID > 254) _nodeID = 254;
// Add this device to HAL device list // Add this device to HAL device list
@ -253,35 +356,13 @@ bool RSprotonode::_configure(VPIN vpin, ConfigTypeEnum configType, int paramCoun
int pin = vpin - _firstVpin; int pin = vpin - _firstVpin;
uint16_t pullup = params[0]; uint16_t pullup = params[0];
uint8_t outBuffer[6] = {_nodeID, EXIODPUP, pin, pullup}; uint8_t outBuffer[6] = {EXIODPUP, pin, pullup};
uint8_t responseBuffer[3]; task->doCommand(outBuffer,3);
bus->_busy = true;
bus->updateCrc(outBuffer,4);
if (bus->_txPin != VPIN_NONE) ArduinoPins::fastWriteDigital(bus->_txPin, HIGH);
_serial->write(outBuffer, 6);
_serial->write(initBuffer, 1);
_serial->flush();
if (bus->_txPin != VPIN_NONE) ArduinoPins::fastWriteDigital(bus->_txPin, LOW);
unsigned long startMillis = millis(); unsigned long startMillis = millis();
while (!_serial->available()) { while (resFlag == 0 && millis() - startMillis < 500); // blocking for now
if (millis() - startMillis > 500) return false; if (resFlag != 1) {
}
uint16_t len = 0;
unsigned long startMicros = micros();
bool rxDone = false;
byte tmpByte;
len = _serial->readBytesUntil(0xFE,responseBuffer, 25);
bus->_busy = false;
if (true/*bus->crcGood(responseBuffer,sizeof(responseBuffer)-2)*/) {
if (!testAndStripMasterFlag(responseBuffer)) DIAG(F("Foreign RSproto Device! no master flag from node %d"),_nodeID);
if (responseBuffer[0] == EXIORDY) {
} else {
DIAG(F("EX-IOExpander485 Vpin %u cannot be used as a digital input pin"), pin); DIAG(F("EX-IOExpander485 Vpin %u cannot be used as a digital input pin"), pin);
} }
} else {
DIAG(F("EX-IOExpander485 node %d CRC Error"), _nodeID);
}
} }
int RSprotonode::_configureAnalogIn(VPIN vpin) { int RSprotonode::_configureAnalogIn(VPIN vpin) {
@ -318,84 +399,7 @@ bool RSprotonode::_configure(VPIN vpin, ConfigTypeEnum configType, int paramCoun
} }
void RSprotonode::_begin() { void RSprotonode::_begin() {
//pinMode(bus->_txPin, OUTPUT);
//ArduinoPins::fastWriteDigital(bus->_txPin, LOW);
uint8_t receiveBuffer[5];
uint8_t commandBuffer[7] = {_nodeID, EXIOINIT, (uint8_t)_nPins, (_firstVpin & (uint8_t)0xFF), (_firstVpin >> (uint8_t)8)};
bus->updateCrc(commandBuffer,5);
//_serial->begin(115200);
//ArduinoPins::fastWriteDigital(bus->_txPin, HIGH);
digitalWrite(bus->_txPin,HIGH);
unsigned long startMillis = millis();
_serial->write(commandBuffer, 7);
_serial->write(initBuffer, 1);
_serial->flush();
digitalWrite(bus->_txPin,LOW);
//ArduinoPins::fastWriteDigital(bus->_txPin, LOW);
startMillis = millis();
while (!_serial->available()) {
if (millis() - startMillis >= 500) return;
}
uint16_t len = 0;
unsigned long startMicros = micros();
byte tmpByte;
bool rxDone = false;
len = _serial->readBytesUntil(0xFE,receiveBuffer, 25);
DIAG(F("rxcode:%d from node"),receiveBuffer[1]);
if (receiveBuffer[1] == EXIOPINS /*&& bus->crcGood(receiveBuffer,sizeof(receiveBuffer)-3)*/) {
if (!bus->testAndStripMasterFlag(receiveBuffer)) DIAG(F("Foreign RSproto Device! no master flag from node %d"),_nodeID);
_numDigitalPins = receiveBuffer[1];
_numAnaloguePins = receiveBuffer[2];
// See if we already have suitable buffers assigned
if (_numDigitalPins>0) {
size_t digitalBytesNeeded = (_numDigitalPins + 7) / 8;
if (_digitalPinBytes < digitalBytesNeeded) {
// Not enough space, free any existing buffer and allocate a new one
if (_digitalPinBytes > 0) free(_digitalInputStates);
if ((_digitalInputStates = (byte*) calloc(digitalBytesNeeded, 1)) != NULL) {
_digitalPinBytes = digitalBytesNeeded;
} else {
DIAG(F("EX-IOExpander485 node:%d ERROR alloc %d bytes"), _nodeID, digitalBytesNeeded);
//_deviceState = DEVSTATE_FAILED;
_digitalPinBytes = 0;
return;
}
}
}
if (_numAnaloguePins>0) {
size_t analogueBytesNeeded = _numAnaloguePins * 2;
if (_analoguePinBytes < analogueBytesNeeded) {
// Free any existing buffers and allocate new ones.
if (_analoguePinBytes > 0) {
free(_analogueInputBuffer);
free(_analogueInputStates);
free(_analoguePinMap);
}
_analogueInputStates = (uint8_t*) calloc(analogueBytesNeeded, 1);
_analogueInputBuffer = (uint8_t*) calloc(analogueBytesNeeded, 1);
_analoguePinMap = (uint8_t*) calloc(_numAnaloguePins, 1);
if (_analogueInputStates != NULL &&
_analogueInputBuffer != NULL &&
_analoguePinMap != NULL) {
_analoguePinBytes = analogueBytesNeeded;
} else {
DIAG(F("EX-IOExpander485 node:%d ERROR alloc analog pin bytes"), _nodeID);
//_deviceState = DEVSTATE_FAILED;
_analoguePinBytes = 0;
return;
}
}
}
} else {
DIAG(F("EX-IOExpander485 node:%d ERROR configuring device (CRC: %s)"), _nodeID, bus->crcGood(receiveBuffer,sizeof(receiveBuffer)-2)? "PASS":"FAIL");
//_deviceState = DEVSTATE_FAILED;
return;
}
commandBuffer[0] = _nodeID; commandBuffer[0] = _nodeID;
commandBuffer[1] = EXIOINITA; commandBuffer[1] = EXIOINITA;
bus->updateCrc(commandBuffer,2); bus->updateCrc(commandBuffer,2);
@ -416,9 +420,7 @@ void RSprotonode::_begin() {
DIAG(F("rxcode:%d from node"),receiveBuffer[1]); DIAG(F("rxcode:%d from node"),receiveBuffer[1]);
if (true/*bus->crcGood(receiveBuffer,sizeof(receiveBuffer)-2)*/) { if (true/*bus->crcGood(receiveBuffer,sizeof(receiveBuffer)-2)*/) {
if (!bus->testAndStripMasterFlag(receiveBuffer)) DIAG(F("Foreign RSproto Device! no master flag from node %d"),_nodeID); if (!bus->testAndStripMasterFlag(receiveBuffer)) DIAG(F("Foreign RSproto Device! no master flag from node %d"),_nodeID);
for (int i = 0; i < _numAnaloguePins; i++) {
_analoguePinMap[i] = receiveBuffer[i];
}
} }
uint8_t versionBuffer[5]; uint8_t versionBuffer[5];
commandBuffer[0] = _nodeID; commandBuffer[0] = _nodeID;
@ -441,9 +443,7 @@ void RSprotonode::_begin() {
DIAG(F("rxcode:%d.%d.%d from node"),versionBuffer[1],versionBuffer[2],versionBuffer[3]); DIAG(F("rxcode:%d.%d.%d from node"),versionBuffer[1],versionBuffer[2],versionBuffer[3]);
if (true/*bus->crcGood(versionBuffer,sizeof(versionBuffer)-2)*/) { if (true/*bus->crcGood(versionBuffer,sizeof(versionBuffer)-2)*/) {
if (!bus->testAndStripMasterFlag(versionBuffer)) DIAG(F("Foreign RSproto Device! no master flag from node %d"),_nodeID); if (!bus->testAndStripMasterFlag(versionBuffer)) DIAG(F("Foreign RSproto Device! no master flag from node %d"),_nodeID);
_majorVer = versionBuffer[1];
_minorVer = versionBuffer[2];
_patchVer = versionBuffer[3];
DIAG(F("EX-IOExpander485 device found, node:%d, Version v%d.%d.%d"), _nodeID, _majorVer, _minorVer, _patchVer); DIAG(F("EX-IOExpander485 device found, node:%d, Version v%d.%d.%d"), _nodeID, _majorVer, _minorVer, _patchVer);
} }
#ifdef DIAG_IO #ifdef DIAG_IO

View File

@ -46,6 +46,67 @@
#include "IODevice.h" #include "IODevice.h"
class RSproto; class RSproto;
class RSprotonode;
#ifndef COMMAND_BUFFER_SIZE
#define COMMAND_BUFFER_SIZE 100
#endif
#ifndef RS485_SERIAL
#define RS485_SERIAL Serial1
#endif
class taskBuffer
{
private:
static taskBuffer * first;
RSprotonode *node;
Stream * serial;
uint8_t _txPin;
uint8_t _nodeID;
uint8_t _commandType;
byte bufferLength;
byte buffer[COMMAND_BUFFER_SIZE];
taskBuffer * next;
uint8_t endChar[1] = {0xFE};
byte inCommandPayload;
// EX-IOExpander protocol flags
enum {
EXIOINIT = 0xE0, // Flag to initialise setup procedure
EXIORDY = 0xE1, // Flag we have completed setup procedure, also for EX-IO to ACK setup
EXIODPUP = 0xE2, // Flag we're sending digital pin pullup configuration
EXIOVER = 0xE3, // Flag to get version
EXIORDAN = 0xE4, // Flag to read an analogue input
EXIOWRD = 0xE5, // Flag for digital write
EXIORDD = 0xE6, // Flag to read digital input
EXIOENAN = 0xE7, // Flag to enable an analogue pin
EXIOINITA = 0xE8, // Flag we're receiving analogue pin mappings
EXIOPINS = 0xE9, // Flag we're receiving pin counts for buffers
EXIOWRAN = 0xEA, // Flag we're sending an analogue write (PWM)
EXIOERR = 0xEF, // Flag we've received an error
};
// RSproto protocol frame bytes
enum {
STARTBYTE = 0xFD,
ENDBYTE = 0xFE,
};
uint16_t _calculateCrc(uint8_t *buf, uint16_t len);
void doCommand2(uint8_t *commandBuffer=NULL, int commandSize=0);
void loop2();
void parseRx(uint8_t *buf);
void parseOne(uint8_t *buf);
public:
taskBuffer(Stream * myserial);
~taskBuffer();
void updateCrc(uint8_t *crcBuf, uint8_t *buf, uint16_t len);
bool crcGood(uint8_t *buf, uint16_t len);
static void doCommand(uint8_t *commandBuffer=NULL, int commandSize=0);
static void init(unsigned long baud, uint16_t cycleTimeMS=500, int8_t txPin=-1);
static void loop();
};
/********************************************************************** /**********************************************************************
* RSprotonode class * RSprotonode class
@ -62,6 +123,7 @@ private:
RSprotonode *_next = NULL; RSprotonode *_next = NULL;
bool _initialised = false; bool _initialised = false;
RSproto *bus; RSproto *bus;
taskBuffer *task;
HardwareSerial* _serial; HardwareSerial* _serial;
// EX-IOExpander protocol flags // EX-IOExpander protocol flags
enum { enum {
@ -78,7 +140,7 @@ private:
EXIOWRAN = 0xEA, // Flag we're sending an analogue write (PWM) EXIOWRAN = 0xEA, // Flag we're sending an analogue write (PWM)
EXIOERR = 0xEF, // Flag we've received an error EXIOERR = 0xEF, // Flag we've received an error
}; };
static RSprotonode *_nodeList;
public: public:
enum ProfileType : int { enum ProfileType : int {
Instant = 0, // Moves immediately between positions (if duration not specified) Instant = 0, // Moves immediately between positions (if duration not specified)
@ -105,7 +167,8 @@ public:
uint8_t _digitalPinBytes = 0; // Size of allocated memory buffer (may be longer than needed) uint8_t _digitalPinBytes = 0; // Size of allocated memory buffer (may be longer than needed)
uint8_t _analoguePinBytes = 0; // Size of allocated memory buffer (may be longer than needed) uint8_t _analoguePinBytes = 0; // Size of allocated memory buffer (may be longer than needed)
uint8_t* _analoguePinMap = NULL; uint8_t* _analoguePinMap = NULL;
uint8_t initBuffer[1] = {0xFE}; int resFlag = 0;
bool _initalized; bool _initalized;
static void create(VPIN firstVpin, int nPins, uint8_t nodeID) { static void create(VPIN firstVpin, int nPins, uint8_t nodeID) {
if (checkNoOverlap(firstVpin, nPins)) new RSprotonode(firstVpin, nPins, nodeID); if (checkNoOverlap(firstVpin, nPins)) new RSprotonode(firstVpin, nPins, nodeID);
@ -119,6 +182,13 @@ public:
RSprotonode *getNext() { RSprotonode *getNext() {
return _next; return _next;
} }
static RSprotonode *findNode(uint8_t nodeID) {
for (RSprotonode *node = _nodeList; node != NULL; node = node->getNext()) {
if (node->getNodeID() == nodeID)
return node;
}
return NULL;
}
void setNext(RSprotonode *node) { void setNext(RSprotonode *node) {
_next = node; _next = node;
} }
@ -170,7 +240,7 @@ class RSproto : public IODevice {
private: private:
// Here we define the device-specific variables. // Here we define the device-specific variables.
uint8_t _busNo; uint8_t _busNo;
taskBuffer *task;
unsigned long _cycleStartTime = 0; unsigned long _cycleStartTime = 0;
unsigned long _timeoutStart = 0; unsigned long _timeoutStart = 0;
unsigned long _cycleTime; // target time between successive read/write cycles, microseconds unsigned long _cycleTime; // target time between successive read/write cycles, microseconds
@ -196,22 +266,8 @@ private:
const unsigned long _digitalRefresh = 10000UL; // Delay refreshing digital inputs for 10ms const unsigned long _digitalRefresh = 10000UL; // Delay refreshing digital inputs for 10ms
const unsigned long _analogueRefresh = 50000UL; // Delay refreshing analogue inputs for 50ms const unsigned long _analogueRefresh = 50000UL; // Delay refreshing analogue inputs for 50ms
// EX-IOExpander protocol flags
enum {
EXIOINIT = 0xE0, // Flag to initialise setup procedure
EXIORDY = 0xE1, // Flag we have completed setup procedure, also for EX-IO to ACK setup
EXIODPUP = 0xE2, // Flag we're sending digital pin pullup configuration
EXIOVER = 0xE3, // Flag to get version
EXIORDAN = 0xE4, // Flag to read an analogue input
EXIOWRD = 0xE5, // Flag for digital write
EXIORDD = 0xE6, // Flag to read digital input
EXIOENAN = 0xE7, // Flag to enable an analogue pin
EXIOINITA = 0xE8, // Flag we're receiving analogue pin mappings
EXIOPINS = 0xE9, // Flag we're receiving pin counts for buffers
EXIOWRAN = 0xEA, // Flag we're sending an analogue write (PWM)
EXIOERR = 0xEF, // Flag we've received an error
};
uint16_t _calculateCrc(uint8_t *buf, uint16_t len);
RSprotonode *_nodeListStart = NULL, *_nodeListEnd = NULL; RSprotonode *_nodeListStart = NULL, *_nodeListEnd = NULL;
RSprotonode *_currentNode = NULL; RSprotonode *_currentNode = NULL;
@ -237,7 +293,6 @@ public:
bool _busy = false; bool _busy = false;
unsigned long _baud; unsigned long _baud;
int taskCnt = 0; int taskCnt = 0;
HardwareSerial *_serialD;
uint8_t initBuffer[1] = {0xFE}; uint8_t initBuffer[1] = {0xFE};
bool testAndStripMasterFlag(uint8_t *buf) { bool testAndStripMasterFlag(uint8_t *buf) {
if (buf[0] != 0xFD) return false; // why did we not get a master flag? bad node? if (buf[0] != 0xFD) return false; // why did we not get a master flag? bad node?
@ -246,18 +301,15 @@ public:
} }
void updateCrc(uint8_t *buf, uint16_t len);
bool crcGood(uint8_t *buf, uint16_t len);
void clearRxBuffer(); void clearRxBuffer();
static void create(HardwareSerial& serial, unsigned long baud, uint16_t cycleTimeMS=500, int8_t txPin=-1, int waitA=10) { static void create(unsigned long baud, uint16_t cycleTimeMS=500, int8_t txPin=-1, int waitA=10) {
new RSproto(serial, baud, cycleTimeMS, txPin, waitA); new RSproto(baud, cycleTimeMS, txPin, waitA);
} }
// Device-specific initialisation // Device-specific initialisation
void _begin() override { void _begin() override {
_serialD->begin(_baud, SERIAL_8N1);
_serialD->flush();
#if defined(RSproto_STM_OK) #if defined(RSproto_STM_OK)
pinMode(RSproto_STM_OK, OUTPUT); pinMode(RSproto_STM_OK, OUTPUT);
ArduinoPins::fastWriteDigital(RSproto_STM_OK,LOW); ArduinoPins::fastWriteDigital(RSproto_STM_OK,LOW);
@ -315,7 +367,7 @@ public:
} }
protected: protected:
RSproto(HardwareSerial &serial, unsigned long baud, uint16_t cycleTimeMS, int8_t txPin, int waitA); RSproto(unsigned long baud, uint16_t cycleTimeMS, int8_t txPin, int waitA);
public: public: