1
0
mirror of https://github.com/DCC-EX/CommandStation-EX.git synced 2024-11-25 00:56:13 +01:00

Compare commits

..

1 Commits

Author SHA1 Message Date
Colin Murdoch
ae1c1d0e9a Added OnOverload
Added code for OnOverload EXRAIL command.  Untested at this point.
2023-08-06 21:00:52 +01:00
41 changed files with 476 additions and 870 deletions

View File

@ -168,7 +168,7 @@ void CommandDistributor::broadcastClockTime(int16_t time, int8_t rate) {
// be safe for both types. // be safe for both types.
broadcastReply(COMMAND_TYPE, F("<jC %d %d>\n"),time, rate); broadcastReply(COMMAND_TYPE, F("<jC %d %d>\n"),time, rate);
#ifdef CD_HANDLE_RING #ifdef CD_HANDLE_RING
broadcastReply(WITHROTTLE_TYPE, F("PFT%l<;>%d\n"), (int32_t)time*60, rate); broadcastReply(WITHROTTLE_TYPE, F("PFT%d<;>%d\n"), time*60, rate);
#endif #endif
} }
@ -205,39 +205,6 @@ int16_t CommandDistributor::retClockTime() {
void CommandDistributor::broadcastLoco(byte slot) { void CommandDistributor::broadcastLoco(byte slot) {
DCC::LOCO * sp=&DCC::speedTable[slot]; DCC::LOCO * sp=&DCC::speedTable[slot];
broadcastReply(COMMAND_TYPE, F("<l %d %d %d %l>\n"), sp->loco,slot,sp->speedCode,sp->functions); broadcastReply(COMMAND_TYPE, F("<l %d %d %d %l>\n"), sp->loco,slot,sp->speedCode,sp->functions);
#ifdef SABERTOOTH
if (Serial2 && sp->loco == SABERTOOTH) {
static uint8_t rampingmode = 0;
bool direction = (sp->speedCode & 0x80) !=0; // true for forward
int32_t speed = sp->speedCode & 0x7f;
if (speed == 1) { // emergency stop
if (rampingmode != 1) {
rampingmode = 1;
Serial2.print("R1: 0\r\n");
Serial2.print("R2: 0\r\n");
}
Serial2.print("MD: 0\r\n");
} else {
if (speed != 0) {
// speed is here 2 to 127
speed = (speed - 1) * 1625 / 100;
speed = speed * (direction ? 1 : -1);
// speed is here -2047 to 2047
}
if (rampingmode != 2) {
rampingmode = 2;
Serial2.print("R1: 2047\r\n");
Serial2.print("R2: 2047\r\n");
}
Serial2.print("M1: ");
Serial2.print(speed);
Serial2.print("\r\n");
Serial2.print("M2: ");
Serial2.print(speed);
Serial2.print("\r\n");
}
}
#endif
#ifdef CD_HANDLE_RING #ifdef CD_HANDLE_RING
WiThrottle::markForBroadcast(sp->loco); WiThrottle::markForBroadcast(sp->loco);
#endif #endif
@ -261,8 +228,11 @@ void CommandDistributor::broadcastPower() {
LCD(2,F("Power %S%S"),state=='1'?F("On"):F("Off"),reason); LCD(2,F("Power %S%S"),state=='1'?F("On"):F("Off"),reason);
} }
void CommandDistributor::broadcastRaw(clientType type, char * msg) { void CommandDistributor::broadcastText(const FSH * msg) {
broadcastReply(type, F("%s"),msg); broadcastReply(COMMAND_TYPE, F("<I %S>\n"),msg);
#ifdef CD_HANDLE_RING
broadcastReply(WITHROTTLE_TYPE, F("Hm%S\n"), msg);
#endif
} }
void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr) { void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr) {

View File

@ -35,9 +35,8 @@
#endif #endif
class CommandDistributor { class CommandDistributor {
public:
enum clientType: byte {NONE_TYPE,COMMAND_TYPE,WITHROTTLE_TYPE};
private: private:
enum clientType: byte {NONE_TYPE,COMMAND_TYPE,WITHROTTLE_TYPE};
static void broadcastToClients(clientType type); static void broadcastToClients(clientType type);
static StringBuffer * broadcastBufferWriter; static StringBuffer * broadcastBufferWriter;
#ifdef CD_HANDLE_RING #ifdef CD_HANDLE_RING
@ -53,7 +52,7 @@ public :
static void setClockTime(int16_t time, int8_t rate, byte opt); static void setClockTime(int16_t time, int8_t rate, byte opt);
static int16_t retClockTime(); static int16_t retClockTime();
static void broadcastPower(); static void broadcastPower();
static void broadcastRaw(clientType type,char * msg); static void broadcastText(const FSH * msg);
static void broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr); static void broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr);
template<typename... Targs> static void broadcastReply(clientType type, Targs... msg); template<typename... Targs> static void broadcastReply(clientType type, Targs... msg);
static void forget(byte clientId); static void forget(byte clientId);

View File

@ -30,7 +30,6 @@
* © 2021 Neil McKechnie * © 2021 Neil McKechnie
* © 2020-2021 Chris Harlow, Harald Barth, David Cutting, * © 2020-2021 Chris Harlow, Harald Barth, David Cutting,
* Fred Decker, Gregor Baues, Anthony W - Dayton * Fred Decker, Gregor Baues, Anthony W - Dayton
* © 2023 Nathan Kellenicki
* All rights reserved. * All rights reserved.
* *
* This file is part of CommandStation-EX * This file is part of CommandStation-EX
@ -79,12 +78,6 @@ void setup()
// Initialise HAL layer before reading EEprom or setting up MotorDrivers // Initialise HAL layer before reading EEprom or setting up MotorDrivers
IODevice::begin(); IODevice::begin();
// As the setup of a motor shield may require a read of the current sense input from the ADC,
// let's make sure to initialise the ADCee class!
ADCee::begin();
// Set up MotorDrivers early to initialize all pins
TrackManager::Setup(MOTOR_SHIELD_TYPE);
DISPLAY_START ( DISPLAY_START (
// This block is still executed for DIAGS if display not in use // This block is still executed for DIAGS if display not in use
LCD(0,F("DCC-EX v%S"),F(VERSION)); LCD(0,F("DCC-EX v%S"),F(VERSION));
@ -96,19 +89,26 @@ void setup()
// Start Ethernet if it exists // Start Ethernet if it exists
#ifndef ARDUINO_ARCH_ESP32 #ifndef ARDUINO_ARCH_ESP32
#if WIFI_ON #if WIFI_ON
WifiInterface::setup(WIFI_SERIAL_LINK_SPEED, F(WIFI_SSID), F(WIFI_PASSWORD), F(WIFI_HOSTNAME), IP_PORT, WIFI_CHANNEL, WIFI_FORCE_AP); WifiInterface::setup(WIFI_SERIAL_LINK_SPEED, F(WIFI_SSID), F(WIFI_PASSWORD), F(WIFI_HOSTNAME), IP_PORT, WIFI_CHANNEL);
#endif // WIFI_ON #endif // WIFI_ON
#else #else
// ESP32 needs wifi on always // ESP32 needs wifi on always
WifiESP::setup(WIFI_SSID, WIFI_PASSWORD, WIFI_HOSTNAME, IP_PORT, WIFI_CHANNEL, WIFI_FORCE_AP); WifiESP::setup(WIFI_SSID, WIFI_PASSWORD, WIFI_HOSTNAME, IP_PORT, WIFI_CHANNEL);
#endif // ARDUINO_ARCH_ESP32 #endif // ARDUINO_ARCH_ESP32
#if ETHERNET_ON #if ETHERNET_ON
EthernetInterface::setup(); EthernetInterface::setup();
#endif // ETHERNET_ON #endif // ETHERNET_ON
// As the setup of a motor shield may require a read of the current sense input from the ADC,
// let's make sure to initialise the ADCee class!
ADCee::begin();
// Responsibility 3: Start the DCC engine. // Responsibility 3: Start the DCC engine.
DCC::begin(); // Note: this provides DCC with two motor drivers, main and prog, which handle the motor shield(s)
// Standard supported devices have pre-configured macros but custome hardware installations require
// detailed pin mappings and may also require modified subclasses of the MotorDriver to implement specialist logic.
// STANDARD_MOTOR_SHIELD, POLOLU_MOTOR_SHIELD, FIREBOX_MK1, FIREBOX_MK1S are pre defined in MotorShields.h
TrackManager::Setup(MOTOR_SHIELD_TYPE);
// Start RMFT aka EX-RAIL (ignored if no automnation) // Start RMFT aka EX-RAIL (ignored if no automnation)
RMFT::begin(); RMFT::begin();

View File

@ -60,7 +60,8 @@ const byte FN_GROUP_5=0x10;
FSH* DCC::shieldName=NULL; FSH* DCC::shieldName=NULL;
byte DCC::globalSpeedsteps=128; byte DCC::globalSpeedsteps=128;
void DCC::begin() { void DCC::begin(const FSH * motorShieldName) {
shieldName=(FSH *)motorShieldName;
StringFormatter::send(&USB_SERIAL,F("<iDCC-EX V-%S / %S / %S G-%S>\n"), F(VERSION), F(ARDUINO_TYPE), shieldName, F(GITHUB_SHA)); StringFormatter::send(&USB_SERIAL,F("<iDCC-EX V-%S / %S / %S G-%S>\n"), F(VERSION), F(ARDUINO_TYPE), shieldName, F(GITHUB_SHA));
#ifndef DISABLE_EEPROM #ifndef DISABLE_EEPROM
// Load stuff from EEprom // Load stuff from EEprom
@ -692,7 +693,7 @@ void DCC::updateLocoReminder(int loco, byte speedCode) {
if (loco==0) { if (loco==0) {
// broadcast stop/estop but dont change direction // broadcast stop/estop but dont change direction
for (int reg = 0; reg <= highestUsedReg; reg++) { for (int reg = 0; reg < highestUsedReg; reg++) {
if (speedTable[reg].loco==0) continue; if (speedTable[reg].loco==0) continue;
byte newspeed=(speedTable[reg].speedCode & 0x80) | (speedCode & 0x7f); byte newspeed=(speedTable[reg].speedCode & 0x80) | (speedCode & 0x7f);
if (speedTable[reg].speedCode != newspeed) { if (speedTable[reg].speedCode != newspeed) {

5
DCC.h
View File

@ -51,10 +51,7 @@ const byte MAX_LOCOS = 30;
class DCC class DCC
{ {
public: public:
static inline void setShieldName(const FSH * motorShieldName) { static void begin(const FSH * motorShieldName);
shieldName=(FSH *)motorShieldName;
};
static void begin();
static void loop(); static void loop();
// Public DCC API functions // Public DCC API functions

View File

@ -152,7 +152,7 @@ byte DCCACK::getAck() {
return(0); // pending set off but not detected means no ACK. return(0); // pending set off but not detected means no ACK.
} }
#ifndef DISABLE_PROG
void DCCACK::loop() { void DCCACK::loop() {
while (ackManagerProg) { while (ackManagerProg) {
byte opcode=GETFLASH(ackManagerProg); byte opcode=GETFLASH(ackManagerProg);
@ -414,7 +414,7 @@ void DCCACK::callback(int value) {
(ackManagerCallback)( value); (ackManagerCallback)( value);
} }
} }
#endif
void DCCACK::checkAck(byte sentResetsSincePacket) { void DCCACK::checkAck(byte sentResetsSincePacket) {
if (!ackPending) return; if (!ackPending) return;

View File

@ -3,7 +3,7 @@
* © 2021 Neil McKechnie * © 2021 Neil McKechnie
* © 2021 Mike S * © 2021 Mike S
* © 2021 Herb Morton * © 2021 Herb Morton
* © 2020-2023 Harald Barth * © 2020-2022 Harald Barth
* © 2020-2021 M Steve Todd * © 2020-2021 M Steve Todd
* © 2020-2021 Fred Decker * © 2020-2021 Fred Decker
* © 2020-2021 Chris Harlow * © 2020-2021 Chris Harlow
@ -47,14 +47,16 @@
#define SENDFLASHLIST(stream,flashList) \ #define SENDFLASHLIST(stream,flashList) \
for (int16_t i=0;;i+=sizeof(flashList[0])) { \ for (int16_t i=0;;i+=sizeof(flashList[0])) { \
int16_t value=GETHIGHFLASHW(flashList,i); \ int16_t value=GETHIGHFLASHW(flashList,i); \
if (value==INT16_MAX) break; \ if (value==0) break; \
if (value != 0) StringFormatter::send(stream,F(" %d"),value); \ StringFormatter::send(stream,F(" %d"),value); \
} }
// These keywords are used in the <1> command. The number is what you get if you use the keyword as a parameter. // These keywords are used in the <1> command. The number is what you get if you use the keyword as a parameter.
// To discover new keyword numbers , use the <$ YOURKEYWORD> command // To discover new keyword numbers , use the <$ YOURKEYWORD> command
const int16_t HASH_KEYWORD_PROG = -29718;
const int16_t HASH_KEYWORD_MAIN = 11339; const int16_t HASH_KEYWORD_MAIN = 11339;
const int16_t HASH_KEYWORD_JOIN = -30750;
const int16_t HASH_KEYWORD_CABS = -11981; const int16_t HASH_KEYWORD_CABS = -11981;
const int16_t HASH_KEYWORD_RAM = 25982; const int16_t HASH_KEYWORD_RAM = 25982;
const int16_t HASH_KEYWORD_CMD = 9962; const int16_t HASH_KEYWORD_CMD = 9962;
@ -62,11 +64,7 @@ const int16_t HASH_KEYWORD_ACK = 3113;
const int16_t HASH_KEYWORD_ON = 2657; const int16_t HASH_KEYWORD_ON = 2657;
const int16_t HASH_KEYWORD_DCC = 6436; const int16_t HASH_KEYWORD_DCC = 6436;
const int16_t HASH_KEYWORD_SLOW = -17209; const int16_t HASH_KEYWORD_SLOW = -17209;
#ifndef DISABLE_PROG
const int16_t HASH_KEYWORD_JOIN = -30750;
const int16_t HASH_KEYWORD_PROG = -29718;
const int16_t HASH_KEYWORD_PROGBOOST = -6353; const int16_t HASH_KEYWORD_PROGBOOST = -6353;
#endif
#ifndef DISABLE_EEPROM #ifndef DISABLE_EEPROM
const int16_t HASH_KEYWORD_EEPROM = -7168; const int16_t HASH_KEYWORD_EEPROM = -7168;
#endif #endif
@ -219,9 +217,6 @@ void DCCEXParser::parse(Print *stream, byte *com, RingStream *ringStream) {
void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
{ {
#ifdef DISABLE_PROG
(void)ringStream;
#endif
#ifndef DISABLE_EEPROM #ifndef DISABLE_EEPROM
(void)EEPROM; // tell compiler not to warn this is unused (void)EEPROM; // tell compiler not to warn this is unused
#endif #endif
@ -291,8 +286,6 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
if (direction < 0 || direction > 1) if (direction < 0 || direction > 1)
break; // invalid direction code break; // invalid direction code
if (cab > 10239 || cab < 0)
break; // beyond DCC range
DCC::setThrottle(cab, tspeed, direction); DCC::setThrottle(cab, tspeed, direction);
if (params == 4) // send obsolete format T response if (params == 4) // send obsolete format T response
@ -376,7 +369,6 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
return; return;
break; break;
#ifndef DISABLE_PROG
case 'w': // WRITE CV on MAIN <w CAB CV VALUE> case 'w': // WRITE CV on MAIN <w CAB CV VALUE>
DCC::writeCVByteMain(p[0], p[1], p[2]); DCC::writeCVByteMain(p[0], p[1], p[2]);
return; return;
@ -384,12 +376,9 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
case 'b': // WRITE CV BIT ON MAIN <b CAB CV BIT VALUE> case 'b': // WRITE CV BIT ON MAIN <b CAB CV BIT VALUE>
DCC::writeCVBitMain(p[0], p[1], p[2], p[3]); DCC::writeCVBitMain(p[0], p[1], p[2], p[3]);
return; return;
#endif
case 'M': // WRITE TRANSPARENT DCC PACKET MAIN <M REG X1 ... X9> case 'M': // WRITE TRANSPARENT DCC PACKET MAIN <M REG X1 ... X9>
#ifndef DISABLE_PROG
case 'P': // WRITE TRANSPARENT DCC PACKET PROG <P REG X1 ... X9> case 'P': // WRITE TRANSPARENT DCC PACKET PROG <P REG X1 ... X9>
#endif
// NOTE: this command was parsed in HEX instead of decimal // NOTE: this command was parsed in HEX instead of decimal
params--; // drop REG params--; // drop REG
if (params<1) break; if (params<1) break;
@ -404,7 +393,6 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
} }
return; return;
#ifndef DISABLE_PROG
case 'W': // WRITE CV ON PROG <W CV VALUE CALLBACKNUM CALLBACKSUB> case 'W': // WRITE CV ON PROG <W CV VALUE CALLBACKNUM CALLBACKSUB>
if (!stashCallback(stream, p, ringStream)) if (!stashCallback(stream, p, ringStream))
break; break;
@ -462,7 +450,6 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
return; return;
} }
break; break;
#endif
case '1': // POWERON <1 [MAIN|PROG|JOIN]> case '1': // POWERON <1 [MAIN|PROG|JOIN]>
{ {
@ -470,29 +457,27 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
bool prog=false; bool prog=false;
bool join=false; bool join=false;
if (params > 1) break; if (params > 1) break;
if (params==0) { // All if (params==0 || MotorDriver::commonFaultPin) { // <1> or tracks can not be handled individually
main=true; main=true;
prog=true; prog=true;
} }
if (params==1) { if (params==1) {
if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN> if (p[0] == HASH_KEYWORD_JOIN) { // <1 JOIN>
main=true;
}
#ifndef DISABLE_PROG
else if (p[0] == HASH_KEYWORD_JOIN) { // <1 JOIN>
main=true; main=true;
prog=true; prog=true;
join=true; join=true;
} }
else if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN>
main=true;
}
else if (p[0]==HASH_KEYWORD_PROG) { // <1 PROG> else if (p[0]==HASH_KEYWORD_PROG) { // <1 PROG>
prog=true; prog=true;
} }
#endif
else break; // will reply <X> else break; // will reply <X>
} }
TrackManager::setJoin(join);
if (main) TrackManager::setMainPower(POWERMODE::ON); if (main) TrackManager::setMainPower(POWERMODE::ON);
if (prog) TrackManager::setProgPower(POWERMODE::ON); if (prog) TrackManager::setProgPower(POWERMODE::ON);
TrackManager::setJoin(join);
CommandDistributor::broadcastPower(); CommandDistributor::broadcastPower();
return; return;
@ -503,7 +488,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
bool main=false; bool main=false;
bool prog=false; bool prog=false;
if (params > 1) break; if (params > 1) break;
if (params==0) { // All if (params==0 || MotorDriver::commonFaultPin) { // <0> or tracks can not be handled individually
main=true; main=true;
prog=true; prog=true;
} }
@ -511,20 +496,18 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
if (p[0]==HASH_KEYWORD_MAIN) { // <0 MAIN> if (p[0]==HASH_KEYWORD_MAIN) { // <0 MAIN>
main=true; main=true;
} }
#ifndef DISABLE_PROG
else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG> else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG>
prog=true; prog=true;
} }
#endif
else break; // will reply <X> else break; // will reply <X>
} }
TrackManager::setJoin(false);
if (main) TrackManager::setMainPower(POWERMODE::OFF); if (main) TrackManager::setMainPower(POWERMODE::OFF);
if (prog) { if (prog) {
TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off
TrackManager::setProgPower(POWERMODE::OFF); TrackManager::setProgPower(POWERMODE::OFF);
} }
TrackManager::setJoin(false);
CommandDistributor::broadcastPower(); CommandDistributor::broadcastPower();
return; return;
@ -655,12 +638,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
if (params==1) { if (params==1) {
SENDFLASHLIST(stream,RMFT2::rosterIdList) SENDFLASHLIST(stream,RMFT2::rosterIdList)
} }
else { else StringFormatter::send(stream,F(" %d \"%S\" \"%S\""),
const FSH * functionNames= RMFT2::getRosterFunctions(id); id, RMFT2::getRosterName(id), RMFT2::getRosterFunctions(id));
StringFormatter::send(stream,F(" %d \"%S\" \"%S\""),
id, RMFT2::getRosterName(id),
functionNames == NULL ? RMFT2::getRosterFunctions(0) : functionNames);
}
#endif #endif
StringFormatter::send(stream, F(">\n")); StringFormatter::send(stream, F(">\n"));
return; return;
@ -914,7 +893,6 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
StringFormatter::send(stream, F("Free memory=%d\n"), DCCTimer::getMinimumFreeMemory()); StringFormatter::send(stream, F("Free memory=%d\n"), DCCTimer::getMinimumFreeMemory());
break; break;
#ifndef DISABLE_PROG
case HASH_KEYWORD_ACK: // <D ACK ON/OFF> <D ACK [LIMIT|MIN|MAX|RETRY] Value> case HASH_KEYWORD_ACK: // <D ACK ON/OFF> <D ACK [LIMIT|MIN|MAX|RETRY] Value>
if (params >= 3) { if (params >= 3) {
if (p[1] == HASH_KEYWORD_LIMIT) { if (p[1] == HASH_KEYWORD_LIMIT) {
@ -935,7 +913,6 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
Diag::ACK = onOff; Diag::ACK = onOff;
} }
return true; return true;
#endif
case HASH_KEYWORD_CMD: // <D CMD ON/OFF> case HASH_KEYWORD_CMD: // <D CMD ON/OFF>
Diag::CMD = onOff; Diag::CMD = onOff;
@ -958,11 +935,11 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
Diag::LCN = onOff; Diag::LCN = onOff;
return true; return true;
#endif #endif
#ifndef DISABLE_PROG
case HASH_KEYWORD_PROGBOOST: case HASH_KEYWORD_PROGBOOST:
TrackManager::progTrackBoosted=true; TrackManager::progTrackBoosted=true;
return true; return true;
#endif
case HASH_KEYWORD_RESET: case HASH_KEYWORD_RESET:
DCCTimer::reset(); DCCTimer::reset();
break; // and <X> if we didnt restart break; // and <X> if we didnt restart

View File

@ -194,10 +194,8 @@ int RMTChannel::RMTfillData(const byte buffer[], byte byteCount, byte repeatCoun
setDCCBit1(data + bitcounter-1); // overwrite previous zero bit with one bit setDCCBit1(data + bitcounter-1); // overwrite previous zero bit with one bit
setEOT(data + bitcounter++); // EOT marker setEOT(data + bitcounter++); // EOT marker
dataLen = bitcounter; dataLen = bitcounter;
noInterrupts(); // keep dataReady and dataRepeat consistnet to each other
dataReady = true; dataReady = true;
dataRepeat = repeatCount+1; // repeatCount of 0 means send once dataRepeat = repeatCount+1; // repeatCount of 0 means send once
interrupts();
return 0; return 0;
} }
@ -214,8 +212,6 @@ void IRAM_ATTR RMTChannel::RMTinterrupt() {
if (dataReady) { // if we have new data, fill while preamble is running if (dataReady) { // if we have new data, fill while preamble is running
rmt_fill_tx_items(channel, data, dataLen, preambleLen-1); rmt_fill_tx_items(channel, data, dataLen, preambleLen-1);
dataReady = false; dataReady = false;
if (dataRepeat == 0) // all data should go out at least once
DIAG(F("Channel %d DCC signal lost data"), channel);
} }
if (dataRepeat > 0) // if a repeat count was specified, work on that if (dataRepeat > 0) // if a repeat count was specified, work on that
dataRepeat--; dataRepeat--;

View File

@ -105,14 +105,9 @@ private:
// that an offset can be initialized. // that an offset can be initialized.
class ADCee { class ADCee {
public: public:
// begin is called for any setup that must be done before // init does add the pin to the list of scanned pins (if this
// **init** can be called. On some architectures this involves ADC
// initialisation and clock routing, sampling times etc.
static void begin();
// init adds the pin to the list of scanned pins (if this
// platform's implementation scans pins) and returns the first // platform's implementation scans pins) and returns the first
// read value (which is why it required begin to have been called first!) // read value. It is called before the regular scan is started.
// It must be called before the regular scan is started.
static int init(uint8_t pin); static int init(uint8_t pin);
// read does read the pin value from the scanned cache or directly // read does read the pin value from the scanned cache or directly
// if this is a platform that does not scan. fromISR is a hint if // if this is a platform that does not scan. fromISR is a hint if
@ -121,15 +116,19 @@ public:
static int read(uint8_t pin, bool fromISR=false); static int read(uint8_t pin, bool fromISR=false);
// returns possible max value that the ADC can return // returns possible max value that the ADC can return
static int16_t ADCmax(); static int16_t ADCmax();
// begin is called for any setup that must be done before
// scan can be called.
static void begin();
private: private:
// On platforms that scan, it is called from waveform ISR // On platforms that scan, it is called from waveform ISR
// only on a regular basis. // only on a regular basis.
static void scan(); static void scan();
// bit array of used pins (max 16) // bit array of used pins (max 16)
static uint16_t usedpins; static uint16_t usedpins;
static uint8_t highestPin;
// cached analog values (malloc:ed to actual number of ADC channels) // cached analog values (malloc:ed to actual number of ADC channels)
static int *analogvals; static int *analogvals;
// ids to scan (new way)
static byte *idarr;
// friend so that we can call scan() and begin() // friend so that we can call scan() and begin()
friend class DCCWaveform; friend class DCCWaveform;
}; };

View File

@ -1,6 +1,6 @@
/* /*
* © 2021 Mike S * © 2021 Mike S
* © 2021-2023 Harald Barth * © 2021-2022 Harald Barth
* © 2021 Fred Decker * © 2021 Fred Decker
* © 2021 Chris Harlow * © 2021 Chris Harlow
* © 2021 David Cutting * © 2021 David Cutting
@ -29,9 +29,6 @@
#include <avr/boot.h> #include <avr/boot.h>
#include <avr/wdt.h> #include <avr/wdt.h>
#include "DCCTimer.h" #include "DCCTimer.h"
#ifdef DEBUG_ADC
#include "TrackManager.h"
#endif
INTERRUPT_CALLBACK interruptHandler=0; INTERRUPT_CALLBACK interruptHandler=0;
// Arduino nano, uno, mega etc // Arduino nano, uno, mega etc
@ -131,8 +128,8 @@ void DCCTimer::reset() {
#define NUM_ADC_INPUTS 8 #define NUM_ADC_INPUTS 8
#endif #endif
uint16_t ADCee::usedpins = 0; uint16_t ADCee::usedpins = 0;
uint8_t ADCee::highestPin = 0;
int * ADCee::analogvals = NULL; int * ADCee::analogvals = NULL;
byte *ADCee::idarr = NULL;
static bool ADCusesHighPort = false; static bool ADCusesHighPort = false;
/* /*
@ -142,17 +139,28 @@ static bool ADCusesHighPort = false;
*/ */
int ADCee::init(uint8_t pin) { int ADCee::init(uint8_t pin) {
uint8_t id = pin - A0; uint8_t id = pin - A0;
byte n;
if (id >= NUM_ADC_INPUTS) if (id >= NUM_ADC_INPUTS)
return -1023; return -1023;
if (id > 7) if (id > 7)
ADCusesHighPort = true; ADCusesHighPort = true;
pinMode(pin, INPUT); pinMode(pin, INPUT);
int value = analogRead(pin); int value = analogRead(pin);
if (analogvals == NULL) if (analogvals == NULL) {
analogvals = (int *)calloc(NUM_ADC_INPUTS, sizeof(int)); analogvals = (int *)calloc(NUM_ADC_INPUTS, sizeof(int));
analogvals[id] = value; for (n=0 ; n < NUM_ADC_INPUTS; n++) // set unreasonable value at startup as marker
usedpins |= (1<<id); analogvals[n] = -32768; // 16 bit int min value
if (id > highestPin) highestPin = id; idarr = (byte *)calloc(NUM_ADC_INPUTS+1, sizeof(byte)); // +1 for terminator value
for (n=0 ; n <= NUM_ADC_INPUTS; n++)
idarr[n] = 255; // set 255 as end of array marker
}
analogvals[id] = value; // store before enable by idarr[n]
for (n=0 ; n <= NUM_ADC_INPUTS; n++) {
if (idarr[n] == 255) {
idarr[n] = id;
break;
}
}
return value; return value;
} }
int16_t ADCee::ADCmax() { int16_t ADCee::ADCmax() {
@ -162,14 +170,14 @@ int16_t ADCee::ADCmax() {
* Read function ADCee::read(pin) to get value instead of analogRead(pin) * Read function ADCee::read(pin) to get value instead of analogRead(pin)
*/ */
int ADCee::read(uint8_t pin, bool fromISR) { int ADCee::read(uint8_t pin, bool fromISR) {
(void)fromISR; // AVR does ignore this arg
uint8_t id = pin - A0; uint8_t id = pin - A0;
if ((usedpins & (1<<id) ) == 0) int a;
return -1023;
// we do not need to check (analogvals == NULL) // we do not need to check (analogvals == NULL)
// because usedpins would still be 0 in that case // because usedpins would still be 0 in that case
if (!fromISR) noInterrupts(); noInterrupts();
int a = analogvals[id]; a = analogvals[id];
if (!fromISR) interrupts(); interrupts();
return a; return a;
} }
/* /*
@ -178,8 +186,7 @@ int ADCee::read(uint8_t pin, bool fromISR) {
#pragma GCC push_options #pragma GCC push_options
#pragma GCC optimize ("-O3") #pragma GCC optimize ("-O3")
void ADCee::scan() { void ADCee::scan() {
static byte id = 0; // id and mask are the same thing but it is faster to static byte num = 0; // index into id array
static uint16_t mask = 1; // increment and shift instead to calculate mask from id
static bool waiting = false; static bool waiting = false;
if (waiting) { if (waiting) {
@ -191,49 +198,26 @@ void ADCee::scan() {
low = ADCL; //must read low before high low = ADCL; //must read low before high
high = ADCH; high = ADCH;
bitSet(ADCSRA, ADIF); bitSet(ADCSRA, ADIF);
analogvals[id] = (high << 8) | low; analogvals[idarr[num]] = (high << 8) | low;
// advance at least one track
#ifdef DEBUG_ADC
if (id == 1) TrackManager::track[1]->setBrake(0);
#endif
waiting = false; waiting = false;
id++;
mask = mask << 1;
if (id > highestPin) {
id = 0;
mask = 1;
}
} }
if (!waiting) { if (!waiting) {
if (usedpins == 0) // otherwise we would loop forever // cycle around in-use analogue pins
return; num++;
// look for a valid track to sample or until we are around if (idarr[num] == 255)
while (true) { num = 0;
if (mask & usedpins) {
// start new ADC aquire on id // start new ADC aquire on id
#if defined(ADCSRB) && defined(MUX5) #if defined(ADCSRB) && defined(MUX5)
if (ADCusesHighPort) { // if we ever have started to use high pins) if (ADCusesHighPort) { // if we ever have started to use high pins)
if (id > 7) // if we use a high ADC pin if (idarr[num] > 7) // if we use a high ADC pin
bitSet(ADCSRB, MUX5); // set MUX5 bit bitSet(ADCSRB, MUX5); // set MUX5 bit
else else
bitClear(ADCSRB, MUX5); bitClear(ADCSRB, MUX5);
} }
#endif #endif
ADMUX=(1<<REFS0)|(id & 0x07); //select AVCC as reference and set MUX ADMUX = (1 << REFS0) | (idarr[num] & 0x07); // select AVCC as reference and set MUX
bitSet(ADCSRA,ADSC); // start conversion bitSet(ADCSRA, ADSC); // start conversion
#ifdef DEBUG_ADC
if (id == 1) TrackManager::track[1]->setBrake(1);
#endif
waiting = true; waiting = true;
return;
}
id++;
mask = mask << 1;
if (id > highestPin) {
id = 0;
mask = 1;
}
}
} }
} }
#pragma GCC pop_options #pragma GCC pop_options

View File

@ -180,8 +180,8 @@ void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
return; return;
} }
pin_to_channel[pin] = --cnt_channel; pin_to_channel[pin] = --cnt_channel;
ledcSetup(cnt_channel, 1000, 8);
ledcAttachPin(pin, cnt_channel); ledcAttachPin(pin, cnt_channel);
ledcSetup(cnt_channel, 1000, 8);
} else { } else {
ledcAttachPin(pin, pin_to_channel[pin]); ledcAttachPin(pin, pin_to_channel[pin]);
} }

View File

@ -30,33 +30,29 @@
#ifdef ARDUINO_ARCH_STM32 #ifdef ARDUINO_ARCH_STM32
#include "DCCTimer.h" #include "DCCTimer.h"
#ifdef DEBUG_ADC
#include "TrackManager.h"
#endif
#include "DIAG.h"
#if defined(ARDUINO_NUCLEO_F401RE) || defined(ARDUINO_NUCLEO_F411RE) #if defined(ARDUINO_NUCLEO_F411RE)
// Nucleo-64 boards don't have additional serial ports defined by default // Nucleo-64 boards don't have Serial1 defined by default
HardwareSerial Serial1(PB7, PA15); // Rx=PB7, Tx=PA15 -- CN7 pins 17 and 21 - F411RE HardwareSerial Serial1(PB7, PA15); // Rx=PB7, Tx=PA15 -- CN7 pins 17 and 21 - F411RE
// Serial2 is defined to use USART2 by default, but is in fact used as the diag console // Serial2 is defined to use USART2 by default, but is in fact used as the diag console
// via the debugger on the Nucleo-64. It is therefore unavailable for other DCC-EX uses like WiFi, DFPlayer, etc. // via the debugger on the Nucleo-64. It is therefore unavailable for other DCC-EX uses like WiFi, DFPlayer, etc.
// Let's define Serial6 as an additional serial port (the only other option for the Nucleo-64s) // Let's define Serial6 as an additional serial port (the only other option for the Nucleo-64s)
HardwareSerial Serial6(PA12, PA11); // Rx=PA12, Tx=PA11 -- CN10 pins 12 and 14 - F411RE HardwareSerial Serial6(PA12, PA11); // Rx=PA12, Tx=PA11 -- CN10 pins 12 and 14 - F411RE
#elif defined(ARDUINO_NUCLEO_F446RE) #elif defined(ARDUINO_NUCLEO_F446RE)
// Nucleo-64 boards don't have additional serial ports defined by default // Nucleo-64 boards don't have Serial1 defined by default
// On the F446RE, Serial1 isn't really useable as it's Rx/Tx pair sit on already used D2/D10 pins HardwareSerial Serial1(PA10, PB6); // Rx=PA10 (D2), Tx=PB6 (D10) -- CN10 pins 17 and 9 - F446RE
// HardwareSerial Serial1(PA10, PB6); // Rx=PA10 (D2), Tx=PB6 (D10) -- CN10 pins 17 and 9 - F446RE
// Serial2 is defined to use USART2 by default, but is in fact used as the diag console // Serial2 is defined to use USART2 by default, but is in fact used as the diag console
// via the debugger on the Nucleo-64. It is therefore unavailable for other DCC-EX uses like WiFi, DFPlayer, etc. // via the debugger on the Nucleo-64. It is therefore unavailable for other DCC-EX uses like WiFi, DFPlayer, etc.
// On the F446RE, Serial3 and Serial5 are easy to use: // NB: USART3 and USART6 are available but as yet undefined
HardwareSerial Serial3(PC11, PC10); // Rx=PC11, Tx=PC10 -- USART3 - F446RE #elif defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)
HardwareSerial Serial5(PD2, PC12); // Rx=PC7, Tx=PC6 -- UART5 - F446RE
// On the F446RE, Serial4 and Serial6 also use pins we can't readily map while using the Arduino pins
#elif defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)|| defined(ARDUINO_NUCLEO_F412ZG)
// Nucleo-144 boards don't have Serial1 defined by default // Nucleo-144 boards don't have Serial1 defined by default
HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6 HardwareSerial Serial1(PG9, PG14); // Rx=PG9, Tx=PG14 -- D0, D1 - F412ZG/F446ZE
// Serial3 is defined to use USART3 by default, but is in fact used as the diag console // Serial2 is defined to use USART2 by default, but is in fact used as the diag console
// via the debugger on the Nucleo-144. It is therefore unavailable for other DCC-EX uses like WiFi, DFPlayer, etc. // via the debugger on the Nucleo-144. It is therefore unavailable for other DCC-EX uses like WiFi, DFPlayer, etc.
// NB:
// On all of the above, USART3, and USART6 are available but as yet undefined
// On F446ZE and F429ZI, UART4, UART5 are also available but as yet undefined
// On F429ZI, UART7 and UART8 are also available but as yet undefined
#else #else
#error STM32 board selected is not yet explicitly supported - so Serial1 peripheral is not defined #error STM32 board selected is not yet explicitly supported - so Serial1 peripheral is not defined
#endif #endif
@ -235,16 +231,13 @@ void DCCTimer::reset() {
while(true) {}; while(true) {};
} }
#define NUM_ADC_INPUTS NUM_ANALOG_INPUTS
// TODO: may need to use uint32_t on STMF4xx variants with > 16 analog inputs! // TODO: may need to use uint32_t on STMF4xx variants with > 16 analog inputs!
#if defined(ARDUINO_NUCLEO_F446RE) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) #if defined(ARDUINO_NUCLEO_F446RE) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)
#warning STM32 board selected not fully supported - only use ADC1 inputs 0-15 for current sensing! #warning STM32 board selected not fully supported - only use ADC1 inputs 0-15 for current sensing!
#endif #endif
// For now, define the max of 16 ports - some variants have more, but this not **yet** supported
#define NUM_ADC_INPUTS 16
// #define NUM_ADC_INPUTS NUM_ANALOG_INPUTS
uint16_t ADCee::usedpins = 0; uint16_t ADCee::usedpins = 0;
uint8_t ADCee::highestPin = 0;
int * ADCee::analogvals = NULL; int * ADCee::analogvals = NULL;
uint32_t * analogchans = NULL; uint32_t * analogchans = NULL;
bool adc1configured = false; bool adc1configured = false;
@ -315,9 +308,6 @@ int ADCee::init(uint8_t pin) {
analogvals[id] = value; // Store sampled value analogvals[id] = value; // Store sampled value
analogchans[id] = adcchan; // Keep track of which ADC channel is used for reading this pin analogchans[id] = adcchan; // Keep track of which ADC channel is used for reading this pin
usedpins |= (1 << id); // This pin is now ready usedpins |= (1 << id); // This pin is now ready
if (id > highestPin) highestPin = id; // Store our highest pin in use
DIAG(F("ADCee::init(): value=%d, channel=%d, id=%d"), value, adcchan, id);
return value; return value;
} }
@ -352,13 +342,11 @@ void ADCee::scan() {
// found value // found value
analogvals[id] = ADC1->DR; analogvals[id] = ADC1->DR;
// advance at least one track // advance at least one track
#ifdef DEBUG_ADC // for scope debug TrackManager::track[1]->setBrake(0);
if (id == 1) TrackManager::track[1]->setBrake(0);
#endif
waiting = false; waiting = false;
id++; id++;
mask = mask << 1; mask = mask << 1;
if (id > highestPin) { // the 1 has been shifted out if (id == NUM_ADC_INPUTS+1) {
id = 0; id = 0;
mask = 1; mask = 1;
} }
@ -372,15 +360,13 @@ void ADCee::scan() {
// start new ADC aquire on id // start new ADC aquire on id
ADC1->SQR3 = analogchans[id]; //1st conversion in regular sequence ADC1->SQR3 = analogchans[id]; //1st conversion in regular sequence
ADC1->CR2 |= (1 << 30); //Start 1st conversion SWSTART ADC1->CR2 |= (1 << 30); //Start 1st conversion SWSTART
#ifdef DEBUG_ADC // for scope debug TrackManager::track[1]->setBrake(1);
if (id == 1) TrackManager::track[1]->setBrake(1);
#endif
waiting = true; waiting = true;
return; return;
} }
id++; id++;
mask = mask << 1; mask = mask << 1;
if (id > highestPin) { if (id == NUM_ADC_INPUTS+1) {
id = 0; id = 0;
mask = 1; mask = 1;
} }

View File

@ -247,9 +247,6 @@ void DCCWaveform::schedulePacket(const byte buffer[], byte byteCount, byte repea
pendingPacket[byteCount] = checksum; pendingPacket[byteCount] = checksum;
pendingLength = byteCount + 1; pendingLength = byteCount + 1;
pendingRepeats = repeats; pendingRepeats = repeats;
// DIAG repeated commands (accesories)
// if (pendingRepeats > 0)
// DIAG(F("Repeats=%d on %s track"), pendingRepeats, isMainTrack ? "MAIN" : "PROG");
// The resets will be zero not only now but as well repeats packets into the future // The resets will be zero not only now but as well repeats packets into the future
clearResets(repeats+1); clearResets(repeats+1);
{ {

View File

@ -2,7 +2,7 @@
* © 2021 Neil McKechnie * © 2021 Neil McKechnie
* © 2021-2023 Harald Barth * © 2021-2023 Harald Barth
* © 2020-2023 Chris Harlow * © 2020-2023 Chris Harlow
* © 2022 Colin Murdoch * © 2022-2023 Colin Murdoch
* All rights reserved. * All rights reserved.
* *
* This file is part of CommandStation-EX * This file is part of CommandStation-EX
@ -94,6 +94,8 @@ LookList * RMFT2::onAmberLookup=NULL;
LookList * RMFT2::onGreenLookup=NULL; LookList * RMFT2::onGreenLookup=NULL;
LookList * RMFT2::onChangeLookup=NULL; LookList * RMFT2::onChangeLookup=NULL;
LookList * RMFT2::onClockLookup=NULL; LookList * RMFT2::onClockLookup=NULL;
//CHM
LookList * RMFT2::onOverloadLookup=NULL;
#define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter) #define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter)
#define SKIPOP progCounter+=3 #define SKIPOP progCounter+=3
@ -175,6 +177,8 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
onGreenLookup=LookListLoader(OPCODE_ONGREEN); onGreenLookup=LookListLoader(OPCODE_ONGREEN);
onChangeLookup=LookListLoader(OPCODE_ONCHANGE); onChangeLookup=LookListLoader(OPCODE_ONCHANGE);
onClockLookup=LookListLoader(OPCODE_ONTIME); onClockLookup=LookListLoader(OPCODE_ONTIME);
//CHM
onOverloadLookup=LookListLoader(OPCODE_ONOVERLOAD);
// Second pass startup, define any turnouts or servos, set signals red // Second pass startup, define any turnouts or servos, set signals red
@ -986,6 +990,8 @@ void RMFT2::loop2() {
case OPCODE_ONGREEN: case OPCODE_ONGREEN:
case OPCODE_ONCHANGE: case OPCODE_ONCHANGE:
case OPCODE_ONTIME: case OPCODE_ONTIME:
//CHM
case OPCODE_ONOVERLOAD:
break; break;
@ -1139,6 +1145,15 @@ void RMFT2::clockEvent(int16_t clocktime, bool change) {
handleEvent(F("CLOCK"),onClockLookup,25*60+clocktime%60); handleEvent(F("CLOCK"),onClockLookup,25*60+clocktime%60);
} }
} }
//CHM
void RMFT2::powerEvent(char track, bool overload) {
// Hunt for an ONOVERLOAD for this item
if (Diag::CMD)
DIAG(F("Looking for Power event on track : %c"), track);
if (overload) {
handleEvent(F("POWER"),onOverloadLookup,track);
}
}
void RMFT2::handleEvent(const FSH* reason,LookList* handlers, int16_t id) { void RMFT2::handleEvent(const FSH* reason,LookList* handlers, int16_t id) {
int pc= handlers->find(id); int pc= handlers->find(id);

View File

@ -1,7 +1,7 @@
/* /*
* © 2021 Neil McKechnie * © 2021 Neil McKechnie
* © 2020-2022 Chris Harlow * © 2020-2022 Chris Harlow
* © 2022 Colin Murdoch * © 2022-2023 Colin Murdoch
* © 2023 Harald Barth * © 2023 Harald Barth
* All rights reserved. * All rights reserved.
* *
@ -62,6 +62,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,
OPCODE_ONCHANGE, OPCODE_ONCHANGE,
OPCODE_ONCLOCKTIME, OPCODE_ONCLOCKTIME,
OPCODE_ONTIME, OPCODE_ONTIME,
OPCODE_ONOVERLOAD,
// OPcodes below this point are skip-nesting IF operations // OPcodes below this point are skip-nesting IF operations
// placed here so that they may be skipped as a group // placed here so that they may be skipped as a group
@ -130,6 +131,7 @@ class LookList {
static void activateEvent(int16_t addr, bool active); static void activateEvent(int16_t addr, bool active);
static void changeEvent(int16_t id, bool change); static void changeEvent(int16_t id, bool change);
static void clockEvent(int16_t clocktime, bool change); static void clockEvent(int16_t clocktime, bool change);
static void powerEvent(char track, bool overload);
static const int16_t SERVO_SIGNAL_FLAG=0x4000; static const int16_t SERVO_SIGNAL_FLAG=0x4000;
static const int16_t ACTIVE_HIGH_SIGNAL_FLAG=0x2000; static const int16_t ACTIVE_HIGH_SIGNAL_FLAG=0x2000;
static const int16_t DCC_SIGNAL_FLAG=0x1000; static const int16_t DCC_SIGNAL_FLAG=0x1000;
@ -188,6 +190,9 @@ private:
static LookList * onGreenLookup; static LookList * onGreenLookup;
static LookList * onChangeLookup; static LookList * onChangeLookup;
static LookList * onClockLookup; static LookList * onClockLookup;
//CHM
static LookList * onOverloadLookup;
// Local variables - exist for each instance/task // Local variables - exist for each instance/task
RMFT2 *next; // loop chain RMFT2 *next; // loop chain

View File

@ -1,6 +1,6 @@
/* /*
* © 2020-2022 Chris Harlow. All rights reserved. * © 2020-2022 Chris Harlow. All rights reserved.
* © 2022 Colin Murdoch * © 2022-2023 Colin Murdoch
* © 2023 Harald Barth * © 2023 Harald Barth
* *
* This file is part of CommandStation-EX * This file is part of CommandStation-EX
@ -93,6 +93,8 @@
#undef ONTIME #undef ONTIME
#undef ONCLOCKTIME #undef ONCLOCKTIME
#undef ONCLOCKMINS #undef ONCLOCKMINS
//CHM
#undef ONOVERLOAD
#undef ONGREEN #undef ONGREEN
#undef ONRED #undef ONRED
#undef ONTHROW #undef ONTHROW
@ -217,6 +219,8 @@
#define ONCLOCKMINS(mins) #define ONCLOCKMINS(mins)
#define ONDEACTIVATE(addr,subaddr) #define ONDEACTIVATE(addr,subaddr)
#define ONDEACTIVATEL(linear) #define ONDEACTIVATEL(linear)
//CHM
#define ONOVERLOAD(track_id)
#define ONCLOSE(turnout_id) #define ONCLOSE(turnout_id)
#define ONGREEN(signal_id) #define ONGREEN(signal_id)
#define ONRED(signal_id) #define ONRED(signal_id)

View File

@ -1,7 +1,7 @@
/* /*
* © 2021 Neil McKechnie * © 2021 Neil McKechnie
* © 2020-2022 Chris Harlow * © 2020-2022 Chris Harlow
* © 2022 Colin Murdoch * © 2022-2023 Colin Murdoch
* © 2023 Harald Barth * © 2023 Harald Barth
* All rights reserved. * All rights reserved.
* *
@ -322,6 +322,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = {
#define ONCLOCKMINS(mins) ONCLOCKTIME(25,mins) #define ONCLOCKMINS(mins) ONCLOCKTIME(25,mins)
#define ONDEACTIVATE(addr,subaddr) OPCODE_ONDEACTIVATE,V(addr<<2|subaddr), #define ONDEACTIVATE(addr,subaddr) OPCODE_ONDEACTIVATE,V(addr<<2|subaddr),
#define ONDEACTIVATEL(linear) OPCODE_ONDEACTIVATE,V(linear+3), #define ONDEACTIVATEL(linear) OPCODE_ONDEACTIVATE,V(linear+3),
#define ONOVERLOAD(track_id) OPCODE_ONOVERLOAD,V(track_id),
#define ONGREEN(signal_id) OPCODE_ONGREEN,V(signal_id), #define ONGREEN(signal_id) OPCODE_ONGREEN,V(signal_id),
#define ONRED(signal_id) OPCODE_ONRED,V(signal_id), #define ONRED(signal_id) OPCODE_ONRED,V(signal_id),
#define ONTHROW(turnout_id) OPCODE_ONTHROW,V(turnout_id), #define ONTHROW(turnout_id) OPCODE_ONTHROW,V(turnout_id),

View File

@ -1 +1 @@
#define GITHUB_SHA "devel-202308102205Z" #define GITHUB_SHA "devel-202304172140Z"

View File

@ -50,12 +50,12 @@ EXTurntable::EXTurntable(VPIN firstVpin, int nPins, I2CAddress I2CAddress) {
// Initialisation of EXTurntable // Initialisation of EXTurntable
void EXTurntable::_begin() { void EXTurntable::_begin() {
I2CManager.begin(); I2CManager.begin();
I2CManager.setClock(1000000);
if (I2CManager.exists(_I2CAddress)) { if (I2CManager.exists(_I2CAddress)) {
#ifdef DIAG_IO #ifdef DIAG_IO
_display(); _display();
#endif #endif
} else { } else {
DIAG(F("EX-Turntable I2C:%s device not found"), _I2CAddress.toString());
_deviceState = DEVSTATE_FAILED; _deviceState = DEVSTATE_FAILED;
} }
} }

View File

@ -1,112 +0,0 @@
/*
* © 2021, Neil McKechnie. All rights reserved.
*
* This file is part of DCC++EX API
*
* This is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* It is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/
#ifndef io_pca9555_h
#define io_pca9555_h
#include "IO_GPIOBase.h"
#include "FSH.h"
/////////////////////////////////////////////////////////////////////////////////////////////////////
/*
* IODevice subclass for PCA9555 16-bit I/O expander (NXP & Texas Instruments).
*/
class PCA9555 : public GPIOBase<uint16_t> {
public:
static void create(VPIN vpin, int nPins, uint8_t I2CAddress, int interruptPin=-1) {
new PCA9555(vpin, min(nPins,16), I2CAddress, interruptPin);
}
// Constructor
PCA9555(VPIN vpin, int nPins, uint8_t I2CAddress, int interruptPin=-1)
: GPIOBase<uint16_t>((FSH *)F("PCA9555"), vpin, nPins, I2CAddress, interruptPin)
{
requestBlock.setRequestParams(_I2CAddress, inputBuffer, sizeof(inputBuffer),
outputBuffer, sizeof(outputBuffer));
outputBuffer[0] = REG_INPUT_P0;
}
private:
void _writeGpioPort() override {
I2CManager.write(_I2CAddress, 3, REG_OUTPUT_P0, _portOutputState, _portOutputState>>8);
}
void _writePullups() override {
// Do nothing, pull-ups are always in place for input ports
// This function is here for HAL GPIOBase API compatibilitiy
}
void _writePortModes() override {
// Write 0 to REG_CONF_P0 & REG_CONF_P1 for in-use pins that are outputs, 1 for others.
// PCA9555 & TCA9555, Interrupt is always enabled for raising and falling edge
uint16_t temp = ~(_portMode & _portInUse);
I2CManager.write(_I2CAddress, 3, REG_CONF_P0, temp, temp>>8);
}
void _readGpioPort(bool immediate) override {
if (immediate) {
uint8_t buffer[2];
I2CManager.read(_I2CAddress, buffer, 2, 1, REG_INPUT_P0);
_portInputState = ((uint16_t)buffer[1]<<8) | buffer[0];
/* PCA9555 Int bug fix, from PCA9555 datasheet: "must change command byte to something besides 00h
* after a Read operation to the PCA9555 device or before reading from
* another device"
* Recommended solution, read from REG_OUTPUT_P0, then do nothing with the received data
* Issue not seen during testing, uncomment if needed
*/
//I2CManager.read(_I2CAddress, buffer, 2, 1, REG_OUTPUT_P0);
} 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];
else
_portInputState = 0xffff;
}
void _setupDevice() override {
// HAL API calls
_writePortModes();
_writePullups();
_writeGpioPort();
}
uint8_t inputBuffer[2];
uint8_t outputBuffer[1];
enum {
REG_INPUT_P0 = 0x00,
REG_INPUT_P1 = 0x01,
REG_OUTPUT_P0 = 0x02,
REG_OUTPUT_P1 = 0x03,
REG_POL_INV_P0 = 0x04,
REG_POL_INV_P1 = 0x05,
REG_CONF_P0 = 0x06,
REG_CONF_P1 = 0x07,
};
};
#endif

View File

@ -1,5 +1,4 @@
/* /*
* © 2023, Peter Cole. All rights reserved.
* © 2022, Peter Cole. All rights reserved. * © 2022, Peter Cole. All rights reserved.
* *
* This file is part of EX-CommandStation * This file is part of EX-CommandStation
@ -29,23 +28,9 @@
* ONCHANGE(vpin) - flag when the rotary encoder position has changed from the previous position * ONCHANGE(vpin) - flag when the rotary encoder position has changed from the previous position
* IFRE(vpin, position) - test to see if specified rotary encoder position has been received * IFRE(vpin, position) - test to see if specified rotary encoder position has been received
* *
* Feedback can also be sent to the rotary encoder by using 2 Vpins, and sending a SET()/RESET() to the second Vpin. * Further to this, feedback can be sent to the rotary encoder by using 2 Vpins, and sending a SET()/RESET() to the second Vpin.
* A SET(vpin) will flag that a turntable (or anything else) is in motion, and a RESET(vpin) that the motion has finished. * A SET(vpin) will flag that a turntable (or anything else) is in motion, and a RESET(vpin) that the motion has finished.
* *
* In addition, defining a third Vpin will allow a position number to be sent so that when an EXRAIL automation or some other
* activity has moved a turntable, the position can be reflected in the rotary encoder software. This can be accomplished
* using the EXRAIL SERVO(vpin, position, profile) command, where:
* - vpin = the third defined Vpin (any other is ignored)
* - position = the defined position in the DCC-EX Rotary Encoder software, 0 (Home) to 255
* - profile = Must be defined as per the SERVO() command, but is ignored as it has no relevance
*
* Defining in myAutomation.h requires the device driver to be included in addition to the HAL() statement. Examples:
*
* #include "IO_RotaryEncoder.h"
* HAL(RotaryEncoder, 700, 1, 0x70) // Define single Vpin, no feedback or position sent to rotary encoder software
* HAL(RotaryEncoder, 700, 2, 0x70) // Define two Vpins, feedback only sent to rotary encoder software
* HAL(RotaryEncoder, 700, 3, 0x70) // Define three Vpins, can send feedback and position update to rotary encoder software
*
* Refer to the documentation for further information including the valid activities and examples. * Refer to the documentation for further information including the valid activities and examples.
*/ */
@ -59,88 +44,58 @@
class RotaryEncoder : public IODevice { class RotaryEncoder : public IODevice {
public: public:
// Constructor
RotaryEncoder(VPIN firstVpin, int nPins, I2CAddress i2cAddress){
_firstVpin = firstVpin;
_nPins = nPins;
_I2CAddress = i2cAddress;
addDevice(this);
}
static void create(VPIN firstVpin, int nPins, I2CAddress i2cAddress) { static void create(VPIN firstVpin, int nPins, I2CAddress i2cAddress) {
if (checkNoOverlap(firstVpin, nPins, i2cAddress)) new RotaryEncoder(firstVpin, nPins, i2cAddress); if (checkNoOverlap(firstVpin, nPins, i2cAddress)) new RotaryEncoder(firstVpin, nPins, i2cAddress);
} }
private: private:
// Constructor
RotaryEncoder(VPIN firstVpin, int nPins, I2CAddress i2cAddress){
_firstVpin = firstVpin;
_nPins = nPins;
if (_nPins > 3) {
_nPins = 3;
DIAG(F("RotaryEncoder WARNING:%d vpins defined, only 3 supported"), _nPins);
}
_I2CAddress = i2cAddress;
addDevice(this);
}
// Initiate the device // Initiate the device
void _begin() { void _begin() {
uint8_t _status;
// Attempt to initilalise device
I2CManager.begin(); I2CManager.begin();
if (I2CManager.exists(_I2CAddress)) { if (I2CManager.exists(_I2CAddress)) {
// Send RE_RDY, must receive RE_RDY to be online byte _getVersion[1] = {RE_VER};
_sendBuffer[0] = RE_RDY; I2CManager.read(_I2CAddress, _versionBuffer, 3, _getVersion, 1);
_status = I2CManager.read(_I2CAddress, _rcvBuffer, 1, _sendBuffer, 1);
if (_status == I2C_STATUS_OK) {
if (_rcvBuffer[0] == RE_RDY) {
_sendBuffer[0] = RE_VER;
if (I2CManager.read(_I2CAddress, _versionBuffer, 3, _sendBuffer, 1) == I2C_STATUS_OK) {
_majorVer = _versionBuffer[0]; _majorVer = _versionBuffer[0];
_minorVer = _versionBuffer[1]; _minorVer = _versionBuffer[1];
_patchVer = _versionBuffer[2]; _patchVer = _versionBuffer[2];
} _buffer[0] = RE_OP;
} else { I2CManager.write(_I2CAddress, _buffer, 1);
DIAG(F("RotaryEncoder I2C:%s garbage received: %d"), _I2CAddress.toString(), _rcvBuffer[0]);
_deviceState = DEVSTATE_FAILED;
return;
}
} else {
DIAG(F("RotaryEncoder I2C:%s ERROR connecting"), _I2CAddress.toString());
_deviceState = DEVSTATE_FAILED;
return;
}
#ifdef DIAG_IO #ifdef DIAG_IO
_display(); _display();
#endif #endif
} else { } else {
DIAG(F("RotaryEncoder I2C:%s device not found"), _I2CAddress.toString());
_deviceState = DEVSTATE_FAILED; _deviceState = DEVSTATE_FAILED;
} }
} }
void _loop(unsigned long currentMicros) override { void _loop(unsigned long currentMicros) override {
if (_deviceState == DEVSTATE_FAILED) return; // Return if device has failed I2CManager.read(_I2CAddress, _buffer, 1);
if (_i2crb.isBusy()) return; // Return if I2C operation still in progress _position = _buffer[0];
// This here needs to have a change check, ie. position is a different value.
if (currentMicros - _lastPositionRead > _positionRefresh) { #if defined(EXRAIL_ACTIVE)
_lastPositionRead = currentMicros;
_sendBuffer[0] = RE_READ;
I2CManager.read(_I2CAddress, _rcvBuffer, 1, _sendBuffer, 1, &_i2crb); // Read position from encoder
_position = _rcvBuffer[0];
// If EXRAIL is active, we need to trigger the ONCHANGE() event handler if it's in use
#if defined(EXRAIL_ACTIVE)
if (_position != _previousPosition) { if (_position != _previousPosition) {
_previousPosition = _position; _previousPosition = _position;
RMFT2::changeEvent(_firstVpin, 1); RMFT2::changeEvent(_firstVpin,1);
} else { } else {
RMFT2::changeEvent(_firstVpin, 0); RMFT2::changeEvent(_firstVpin,0);
}
#endif
} }
#endif
delayUntil(currentMicros + 100000);
} }
// Return the position sent by the rotary encoder software // Device specific read function
int _readAnalogue(VPIN vpin) override { int _readAnalogue(VPIN vpin) override {
if (_deviceState == DEVSTATE_FAILED) return 0; if (_deviceState == DEVSTATE_FAILED) return 0;
return _position; return _position;
} }
// Send the feedback value to the rotary encoder software
void _write(VPIN vpin, int value) override { void _write(VPIN vpin, int value) override {
if (vpin == _firstVpin + 1) { if (vpin == _firstVpin + 1) {
if (value != 0) value = 0x01; if (value != 0) value = 0x01;
@ -149,19 +104,6 @@ private:
} }
} }
// Send a position update to the rotary encoder software
// To be valid, must be 0 to 255, and different to the current position
// If the current position is the same, it was initiated by the rotary encoder
void _writeAnalogue(VPIN vpin, int position, uint8_t profile, uint16_t duration) override {
if (vpin == _firstVpin + 2) {
if (position >= 0 && position <= 255 && position != _position) {
byte newPosition = position & 0xFF;
byte _positionBuffer[2] = {RE_MOVE, newPosition};
I2CManager.write(_I2CAddress, _positionBuffer, 2);
}
}
}
void _display() override { void _display() override {
DIAG(F("Rotary Encoder I2C:%s v%d.%d.%d Configured on VPIN:%u-%d %S"), _I2CAddress.toString(), _majorVer, _minorVer, _patchVer, DIAG(F("Rotary Encoder I2C:%s v%d.%d.%d Configured on VPIN:%u-%d %S"), _I2CAddress.toString(), _majorVer, _minorVer, _patchVer,
(int)_firstVpin, _firstVpin+_nPins-1, (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F("")); (int)_firstVpin, _firstVpin+_nPins-1, (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F(""));
@ -170,21 +112,14 @@ private:
int8_t _position; int8_t _position;
int8_t _previousPosition = 0; int8_t _previousPosition = 0;
uint8_t _versionBuffer[3]; uint8_t _versionBuffer[3];
uint8_t _sendBuffer[1]; uint8_t _buffer[1];
uint8_t _rcvBuffer[1];
uint8_t _majorVer = 0; uint8_t _majorVer = 0;
uint8_t _minorVer = 0; uint8_t _minorVer = 0;
uint8_t _patchVer = 0; uint8_t _patchVer = 0;
I2CRB _i2crb;
unsigned long _lastPositionRead = 0;
const unsigned long _positionRefresh = 100000UL; // Delay refreshing position for 100ms
enum { enum {
RE_RDY = 0xA0, // Flag to check if encoder is ready for operation RE_VER = 0xA0, // Flag to retrieve rotary encoder version from the device
RE_VER = 0xA1, // Flag to retrieve rotary encoder software version RE_OP = 0xA1, // Flag for normal operation
RE_READ = 0xA2, // Flag to read the current position of the encoder
RE_OP = 0xA3, // Flag for operation start/end, sent to when sending feedback on move start/end
RE_MOVE = 0xA4, // Flag for sending a position update from the device driver to the encoder
}; };
}; };

View File

@ -4,6 +4,7 @@
* © 2021 Fred Decker * © 2021 Fred Decker
* © 2020-2023 Harald Barth * © 2020-2023 Harald Barth
* © 2020-2021 Chris Harlow * © 2020-2021 Chris Harlow
* © 2023 Colin Murdoch
* All rights reserved. * All rights reserved.
* *
* This file is part of CommandStation-EX * This file is part of CommandStation-EX
@ -26,6 +27,7 @@
#include "DCCWaveform.h" #include "DCCWaveform.h"
#include "DCCTimer.h" #include "DCCTimer.h"
#include "DIAG.h" #include "DIAG.h"
#include "EXRAIL2.h"
unsigned long MotorDriver::globalOverloadStart = 0; unsigned long MotorDriver::globalOverloadStart = 0;
@ -574,6 +576,8 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) {
DIAG(F("TRACK %c FAULT PIN detected after %4M. Pause %4M)"), trackno + 'A', mslpc, power_sample_overload_wait); DIAG(F("TRACK %c FAULT PIN detected after %4M. Pause %4M)"), trackno + 'A', mslpc, power_sample_overload_wait);
throttleInrush(false); throttleInrush(false);
setPower(POWERMODE::OVERLOAD); setPower(POWERMODE::OVERLOAD);
//CHM
RMFT2::powerEvent(trackno + 'A', true); // Tell EXRAIL we have an overload
break; break;
} }
if (checkCurrent(useProgLimit)) { if (checkCurrent(useProgLimit)) {
@ -591,6 +595,8 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) {
trackno + 'A', mA, maxmA, mslpc, power_sample_overload_wait); trackno + 'A', mA, maxmA, mslpc, power_sample_overload_wait);
throttleInrush(false); throttleInrush(false);
setPower(POWERMODE::OVERLOAD); setPower(POWERMODE::OVERLOAD);
//CHM
RMFT2::powerEvent(trackno + 'A', true); // Tell EXRAIL we have an overload
break; break;
} }
// all well // all well

View File

@ -27,10 +27,6 @@
#include "IODevice.h" #include "IODevice.h"
#include "DCCTimer.h" #include "DCCTimer.h"
// use powers of two so we can do logical and/or on the track modes in if clauses.
enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PROG = 4,
TRACK_MODE_DC = 8, TRACK_MODE_DCX = 16, TRACK_MODE_EXT = 32};
#define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH #define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH
#define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW #define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW
#define isHIGH(fastpin) (*fastpin.inout & fastpin.maskHIGH) #define isHIGH(fastpin) (*fastpin.inout & fastpin.maskHIGH)
@ -78,9 +74,8 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO
// Virtualised Motor shield 1-track hardware Interface // Virtualised Motor shield 1-track hardware Interface
#ifndef UNUSED_PIN // sync define with the one in MotorDrivers.h #ifndef UNUSED_PIN // sync define with the one in MotorDrivers.h
#define UNUSED_PIN 255 // inside uint8_t #define UNUSED_PIN 127 // inside int8_t
#endif #endif
#define MAX_PIN 254
class pinpair { class pinpair {
public: public:
@ -111,13 +106,13 @@ extern volatile portreg_t shadowPORTA;
extern volatile portreg_t shadowPORTB; extern volatile portreg_t shadowPORTB;
extern volatile portreg_t shadowPORTC; extern volatile portreg_t shadowPORTC;
enum class POWERMODE : byte { OFF, ON, OVERLOAD, ALERT }; enum class POWERMODE : byte { OFF, ON, OVERLOAD };
class MotorDriver { class MotorDriver {
public: public:
MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin, MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int8_t brake_pin,
byte current_pin, float senseFactor, unsigned int tripMilliamps, int16_t fault_pin); byte current_pin, float senseFactor, unsigned int tripMilliamps, int8_t fault_pin);
void setPower( POWERMODE mode); void setPower( POWERMODE mode);
POWERMODE getPower() { return powerMode;} POWERMODE getPower() { return powerMode;}
// as the port registers can be shadowed to get syncronized DCC signals // as the port registers can be shadowed to get syncronized DCC signals
@ -149,7 +144,6 @@ class MotorDriver {
}; };
inline pinpair getSignalPin() { return pinpair(signalPin,signalPin2); }; inline pinpair getSignalPin() { return pinpair(signalPin,signalPin2); };
void setDCSignal(byte speedByte); void setDCSignal(byte speedByte);
void throttleInrush(bool on);
inline void detachDCSignal() { inline void detachDCSignal() {
#if defined(__arm__) #if defined(__arm__)
pinMode(brakePin, OUTPUT); pinMode(brakePin, OUTPUT);
@ -180,10 +174,7 @@ class MotorDriver {
bool isPWMCapable(); bool isPWMCapable();
bool canMeasureCurrent(); bool canMeasureCurrent();
bool trackPWM = false; // this track uses PWM timer to generate the DCC waveform bool trackPWM = false; // this track uses PWM timer to generate the DCC waveform
bool commonFaultPin = false; // This is a stupid motor shield which has only a common fault pin for both outputs static bool commonFaultPin; // This is a stupid motor shield which has only a common fault pin for both outputs
inline byte setCommonFaultPin() {
return commonFaultPin = true;
}
inline byte getFaultPin() { inline byte getFaultPin() {
return faultPin; return faultPin;
} }
@ -194,46 +185,17 @@ class MotorDriver {
inline void setTrackLetter(char c) { inline void setTrackLetter(char c) {
trackLetter = c; trackLetter = c;
}; };
// this returns how much time has passed since the last power change. If it
// was really long ago (approx > 52min) advance counter approx 35 min so that
// we are at 18 minutes again. Times for 32 bit unsigned long.
inline unsigned long microsSinceLastPowerChange(POWERMODE mode) {
unsigned long now = micros();
unsigned long diff = now - lastPowerChange[(int)mode];
if (diff > (1UL << (7 *sizeof(unsigned long)))) // 2^(4*7)us = 268.4 seconds
lastPowerChange[(int)mode] = now - 30000000UL; // 30 seconds ago
return diff;
};
#ifdef ANALOG_READ_INTERRUPT #ifdef ANALOG_READ_INTERRUPT
bool sampleCurrentFromHW(); bool sampleCurrentFromHW();
void startCurrentFromHW(); void startCurrentFromHW();
#endif #endif
inline void setMode(TRACK_MODE m) {
trackMode = m;
};
inline TRACK_MODE getMode() {
return trackMode;
};
private: private:
char trackLetter = '?'; char trackLetter = '?';
bool isProgTrack = false; // tells us if this is a prog track bool isProgTrack = false; // tells us if this is a prog track
void getFastPin(const FSH* type,int pin, bool input, FASTPIN & result); void getFastPin(const FSH* type,int pin, bool input, FASTPIN & result);
inline void getFastPin(const FSH* type,int pin, FASTPIN & result) { void getFastPin(const FSH* type,int pin, FASTPIN & result) {
getFastPin(type, pin, 0, result); getFastPin(type, pin, 0, result);
}; }
// side effect sets lastCurrent and tripValue
inline bool checkCurrent(bool useProgLimit) {
tripValue= useProgLimit?progTripValue:getRawCurrentTripValue();
lastCurrent = getCurrentRaw();
if (lastCurrent < 0)
lastCurrent = -lastCurrent;
return lastCurrent >= tripValue;
};
// side effect sets lastCurrent
inline bool checkFault() {
lastCurrent = getCurrentRaw();
return lastCurrent < 0;
};
VPIN powerPin; VPIN powerPin;
byte signalPin, signalPin2, currentPin, faultPin, brakePin; byte signalPin, signalPin2, currentPin, faultPin, brakePin;
FASTPIN fastSignalPin, fastSignalPin2, fastBrakePin,fastFaultPin; FASTPIN fastSignalPin, fastSignalPin2, fastBrakePin,fastFaultPin;
@ -254,14 +216,10 @@ class MotorDriver {
int rawCurrentTripValue; int rawCurrentTripValue;
// current sampling // current sampling
POWERMODE powerMode; POWERMODE powerMode;
POWERMODE lastPowerMode; unsigned long lastSampleTaken;
unsigned long lastPowerChange[4]; // timestamp in microseconds unsigned int sampleDelay;
unsigned long lastBadSample; // timestamp in microseconds
// used to sync restore time when common Fault pin detected
static unsigned long globalOverloadStart; // timestamp in microseconds
int progTripValue; int progTripValue;
int lastCurrent; //temp value int lastCurrent;
int tripValue; //temp value
#ifdef ANALOG_READ_INTERRUPT #ifdef ANALOG_READ_INTERRUPT
volatile unsigned long sampleCurrentTimestamp; volatile unsigned long sampleCurrentTimestamp;
volatile uint16_t sampleCurrent; volatile uint16_t sampleCurrent;
@ -269,28 +227,16 @@ class MotorDriver {
int maxmA; int maxmA;
int tripmA; int tripmA;
// Times for overload management. Unit: microseconds. // Wait times for power management. Unit: milliseconds
// Base for wait time until power is turned on again static const int POWER_SAMPLE_ON_WAIT = 100;
static const unsigned long POWER_SAMPLE_OVERLOAD_WAIT = 40000UL; static const int POWER_SAMPLE_OFF_WAIT = 1000;
// Time after we consider all faults old and forgotten static const int POWER_SAMPLE_OVERLOAD_WAIT = 20;
static const unsigned long POWER_SAMPLE_ALL_GOOD = 5000000UL;
// Time after which we consider a ALERT over
static const unsigned long POWER_SAMPLE_ALERT_GOOD = 20000UL;
// How long to ignore fault pin if current is under limit
static const unsigned long POWER_SAMPLE_IGNORE_FAULT_LOW = 100000UL;
// How long to ignore fault pin if current is higher than limit
static const unsigned long POWER_SAMPLE_IGNORE_FAULT_HIGH = 5000UL;
// How long to wait between overcurrent and turning off
static const unsigned long POWER_SAMPLE_IGNORE_CURRENT = 100000UL;
// Upper limit for retry period
static const unsigned long POWER_SAMPLE_RETRY_MAX = 10000000UL;
// Trip current for programming track, 250mA. Change only if you really // Trip current for programming track, 250mA. Change only if you really
// need to be non-NMRA-compliant because of decoders that are not either. // need to be non-NMRA-compliant because of decoders that are not either.
static const int TRIP_CURRENT_PROG=250; static const int TRIP_CURRENT_PROG=250;
unsigned long power_sample_overload_wait = POWER_SAMPLE_OVERLOAD_WAIT; unsigned long power_sample_overload_wait = POWER_SAMPLE_OVERLOAD_WAIT;
unsigned int power_good_counter = 0; unsigned int power_good_counter = 0;
TRACK_MODE trackMode = TRACK_MODE_NONE; // we assume track not assigned at startup
}; };
#endif #endif

View File

@ -1,7 +1,7 @@
/* /*
* © 2022-2023 Paul M. Antoine * © 2022 Paul M. Antoine
* © 2021 Fred Decker * © 2021 Fred Decker
* © 2020-2023 Harald Barth * © 2020-2022 Harald Barth
* (c) 2020 Chris Harlow. All rights reserved. * (c) 2020 Chris Harlow. All rights reserved.
* (c) 2021 Fred Decker. All rights reserved. * (c) 2021 Fred Decker. All rights reserved.
* (c) 2020 Harald Barth. All rights reserved. * (c) 2020 Harald Barth. All rights reserved.
@ -36,7 +36,7 @@
// custom defines in config.h. // custom defines in config.h.
#ifndef UNUSED_PIN // sync define with the one in MotorDriver.h #ifndef UNUSED_PIN // sync define with the one in MotorDriver.h
#define UNUSED_PIN 255 // inside uint8_t #define UNUSED_PIN 127 // inside int8_t
#endif #endif
// The MotorDriver definition is: // The MotorDriver definition is:
@ -60,8 +60,7 @@
// Arduino STANDARD Motor Shield, used on different architectures: // Arduino STANDARD Motor Shield, used on different architectures:
#if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32) #if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32)
// Standard Motor Shield definition for 3v3 processors (other than the ESP32) // Setup for SAMD21 Sparkfun DEV board using Arduino standard Motor Shield R3 (MUST be R3
// Setup for SAMD21 Sparkfun DEV board MUST use Arduino Motor Shield R3 (MUST be R3
// for 3v3 compatibility!!) senseFactor for 3.3v systems is 1.95 as calculated when using // for 3v3 compatibility!!) senseFactor for 3.3v systems is 1.95 as calculated when using
// 10-bit A/D samples, and for 12-bit samples it's more like 0.488, but we probably need // 10-bit A/D samples, and for 12-bit samples it's more like 0.488, but we probably need
// to tweak both these // to tweak both these
@ -71,12 +70,6 @@
#define SAMD_STANDARD_MOTOR_SHIELD STANDARD_MOTOR_SHIELD #define SAMD_STANDARD_MOTOR_SHIELD STANDARD_MOTOR_SHIELD
#define STM32_STANDARD_MOTOR_SHIELD STANDARD_MOTOR_SHIELD #define STM32_STANDARD_MOTOR_SHIELD STANDARD_MOTOR_SHIELD
// EX 8874 based shield connected to a 3V3 system with 12-bit (4096) ADC
#define EX8874_SHIELD F("EX8874"), \
new MotorDriver( 3, 12, UNUSED_PIN, 9, A0, 1.27, 5000, A4), \
new MotorDriver(11, 13, UNUSED_PIN, 8, A1, 1.27, 5000, A5)
#elif defined(ARDUINO_ARCH_ESP32) #elif defined(ARDUINO_ARCH_ESP32)
// STANDARD shield on an ESPDUINO-32 (ESP32 in Uno form factor). The shield must be eiter the // STANDARD shield on an ESPDUINO-32 (ESP32 in Uno form factor). The shield must be eiter the
// 3.3V compatible R3 version or it has to be modified to not supply more than 3.3V to the // 3.3V compatible R3 version or it has to be modified to not supply more than 3.3V to the
@ -87,11 +80,9 @@
new MotorDriver(25/* 3*/, 19/*12*/, UNUSED_PIN, 13/*9*/, 35/*A2*/, 0.70, 1500, UNUSED_PIN), \ new MotorDriver(25/* 3*/, 19/*12*/, UNUSED_PIN, 13/*9*/, 35/*A2*/, 0.70, 1500, UNUSED_PIN), \
new MotorDriver(23/*11*/, 18/*13*/, UNUSED_PIN, 12/*8*/, 34/*A3*/, 0.70, 1500, UNUSED_PIN) new MotorDriver(23/*11*/, 18/*13*/, UNUSED_PIN, 12/*8*/, 34/*A3*/, 0.70, 1500, UNUSED_PIN)
// EX 8874 based shield connected to a 3.3V system (like ESP32) and 12bit (4096) ADC
// numbers are GPIO numbers. comments are UNO form factor shield pin numbers
#define EX8874_SHIELD F("EX8874"),\ #define EX8874_SHIELD F("EX8874"),\
new MotorDriver(25/* 3*/, 19/*12*/, UNUSED_PIN, 13/*9*/, 35/*A2*/, 1.27, 5000, 36 /*A4*/), \ new MotorDriver(25/* 3*/, 19/*12*/, UNUSED_PIN, 13/*9*/, 35/*A2*/, 1.17, 5000, -36 /*-A4*/), \
new MotorDriver(23/*11*/, 18/*13*/, UNUSED_PIN, 12/*8*/, 34/*A3*/, 1.27, 5000, 39 /*A5*/) new MotorDriver(23/*11*/, 18/*13*/, UNUSED_PIN, 12/*8*/, 34/*A3*/, 1.17, 5000, -39 /*-A5*/)
#else #else
// STANDARD shield on any Arduino Uno or Mega compatible with the original specification. // STANDARD shield on any Arduino Uno or Mega compatible with the original specification.
@ -101,12 +92,6 @@
#define BRAKE_PWM_SWAPPED_MOTOR_SHIELD F("BPS_MOTOR_SHIELD"), \ #define BRAKE_PWM_SWAPPED_MOTOR_SHIELD F("BPS_MOTOR_SHIELD"), \
new MotorDriver(-9 , 12, UNUSED_PIN, -3, A0, 2.99, 1500, UNUSED_PIN), \ new MotorDriver(-9 , 12, UNUSED_PIN, -3, A0, 2.99, 1500, UNUSED_PIN), \
new MotorDriver(-8 , 13, UNUSED_PIN,-11, A1, 2.99, 1500, UNUSED_PIN) new MotorDriver(-8 , 13, UNUSED_PIN,-11, A1, 2.99, 1500, UNUSED_PIN)
// EX 8874 based shield connected to a 5V system (like Arduino) and 10bit (1024) ADC
#define EX8874_SHIELD F("EX8874"), \
new MotorDriver( 3, 12, UNUSED_PIN, 9, A0, 5.08, 5000, A4), \
new MotorDriver(11, 13, UNUSED_PIN, 8, A1, 5.08, 5000, A5)
#endif #endif
// Pololu Motor Shield // Pololu Motor Shield
@ -135,6 +120,10 @@
new MotorDriver(2, 7, UNUSED_PIN, -9, A0, 10, 2500, 6), \ new MotorDriver(2, 7, UNUSED_PIN, -9, A0, 10, 2500, 6), \
new MotorDriver(4, 8, UNUSED_PIN, -10, A1, 10, 2500, 12) new MotorDriver(4, 8, UNUSED_PIN, -10, A1, 10, 2500, 12)
#define EX8874_SHIELD F("EX8874"), \
new MotorDriver( 3, 12, UNUSED_PIN, 9, A0, 4.86, 5000, -A4), \
new MotorDriver(11, 13, UNUSED_PIN, 8, A1, 4.86, 5000, -A5)
// Firebox Mk1 // Firebox Mk1
#define FIREBOX_MK1 F("FIREBOX_MK1"), \ #define FIREBOX_MK1 F("FIREBOX_MK1"), \
new MotorDriver(3, 6, 7, UNUSED_PIN, A5, 9.766, 5500, UNUSED_PIN), \ new MotorDriver(3, 6, 7, UNUSED_PIN, A5, 9.766, 5500, UNUSED_PIN), \

View File

@ -87,9 +87,6 @@ void SerialManager::init() {
delay(1000); delay(1000);
} }
#endif #endif
#ifdef SABERTOOTH
Serial2.begin(9600, SERIAL_8N1, 16, 17); // GPIO 16 RXD2; GPIO 17 TXD2 on ESP32
#endif
} }
void SerialManager::broadcast(char * stringBuffer) { void SerialManager::broadcast(char * stringBuffer) {

View File

@ -117,24 +117,6 @@ void StringFormatter::send2(Print * stream,const FSH* format, va_list args) {
case 'o': stream->print(va_arg(args, int), OCT); break; case 'o': stream->print(va_arg(args, int), OCT); break;
case 'x': stream->print((unsigned int)va_arg(args, unsigned int), HEX); break; case 'x': stream->print((unsigned int)va_arg(args, unsigned int), HEX); break;
case 'X': stream->print((unsigned long)va_arg(args, unsigned long), HEX); break; case 'X': stream->print((unsigned long)va_arg(args, unsigned long), HEX); break;
case 'M':
{ // this prints a unsigned long microseconds time in readable format
unsigned long time = va_arg(args, long);
if (time >= 2000) {
time = time / 1000;
if (time >= 2000) {
printPadded(stream, time/1000, formatWidth, formatLeft);
stream->print(F("sec"));
} else {
printPadded(stream,time, formatWidth, formatLeft);
stream->print(F("msec"));
}
} else {
printPadded(stream,time, formatWidth, formatLeft);
stream->print(F("usec"));
}
}
break;
//case 'f': stream->print(va_arg(args, double), 2); break; //case 'f': stream->print(va_arg(args, double), 2); break;
//format width prefix //format width prefix
case '-': case '-':

View File

@ -31,20 +31,19 @@
#define APPLY_BY_MODE(findmode,function) \ #define APPLY_BY_MODE(findmode,function) \
FOR_EACH_TRACK(t) \ FOR_EACH_TRACK(t) \
if (track[t]->getMode()==findmode) \ if (trackMode[t]==findmode) \
track[t]->function; track[t]->function;
#ifndef DISABLE_PROG
const int16_t HASH_KEYWORD_PROG = -29718; const int16_t HASH_KEYWORD_PROG = -29718;
#endif
const int16_t HASH_KEYWORD_MAIN = 11339; const int16_t HASH_KEYWORD_MAIN = 11339;
const int16_t HASH_KEYWORD_OFF = 22479; const int16_t HASH_KEYWORD_OFF = 22479;
const int16_t HASH_KEYWORD_NONE = -26550;
const int16_t HASH_KEYWORD_DC = 2183; const int16_t HASH_KEYWORD_DC = 2183;
const int16_t HASH_KEYWORD_DCX = 6463; // DC reversed polarity const int16_t HASH_KEYWORD_DCX = 6463; // DC reversed polarity
const int16_t HASH_KEYWORD_EXT = 8201; // External DCC signal const int16_t HASH_KEYWORD_EXT = 8201; // External DCC signal
const int16_t HASH_KEYWORD_A = 65; // parser makes single chars the ascii. const int16_t HASH_KEYWORD_A = 65; // parser makes single chars the ascii.
MotorDriver * TrackManager::track[MAX_TRACKS]; MotorDriver * TrackManager::track[MAX_TRACKS];
TRACK_MODE TrackManager::trackMode[MAX_TRACKS];
int16_t TrackManager::trackDCAddr[MAX_TRACKS]; int16_t TrackManager::trackDCAddr[MAX_TRACKS];
POWERMODE TrackManager::mainPowerGuess=POWERMODE::OFF; POWERMODE TrackManager::mainPowerGuess=POWERMODE::OFF;
@ -74,7 +73,7 @@ void TrackManager::sampleCurrent() {
waiting = false; waiting = false;
tr++; tr++;
if (tr > lastTrack) tr = 0; if (tr > lastTrack) tr = 0;
if (lastTrack < 2 || track[tr]->getMode() & TRACK_MODE_PROG) { if (lastTrack < 2 || trackMode[tr] & TRACK_MODE_PROG) {
return; // We could continue but for prog track we return; // We could continue but for prog track we
// rather do it in next interrupt beacuse // rather do it in next interrupt beacuse
// that gives us well defined sampling point. // that gives us well defined sampling point.
@ -85,7 +84,7 @@ void TrackManager::sampleCurrent() {
if (!waiting) { if (!waiting) {
// look for a valid track to sample or until we are around // look for a valid track to sample or until we are around
while (true) { while (true) {
if (track[tr]->getMode() & ( TRACK_MODE_MAIN|TRACK_MODE_PROG|TRACK_MODE_DC|TRACK_MODE_DCX|TRACK_MODE_EXT )) { if (trackMode[tr] & ( TRACK_MODE_MAIN|TRACK_MODE_PROG|TRACK_MODE_DC|TRACK_MODE_DCX|TRACK_MODE_EXT )) {
track[tr]->startCurrentFromHW(); track[tr]->startCurrentFromHW();
// for scope debug track[1]->setBrake(1); // for scope debug track[1]->setBrake(1);
waiting = true; waiting = true;
@ -117,31 +116,19 @@ void TrackManager::Setup(const FSH * shieldname,
// Default the first 2 tracks (which may be null) and perform HA waveform check. // Default the first 2 tracks (which may be null) and perform HA waveform check.
setTrackMode(0,TRACK_MODE_MAIN); setTrackMode(0,TRACK_MODE_MAIN);
#ifndef DISABLE_PROG
setTrackMode(1,TRACK_MODE_PROG); setTrackMode(1,TRACK_MODE_PROG);
#else
setTrackMode(1,TRACK_MODE_MAIN);
#endif
// Fault pin config for odd motor boards (example pololu) // TODO Fault pin config for odd motor boards (example pololu)
FOR_EACH_TRACK(t) { // MotorDriver::commonFaultPin = ((mainDriver->getFaultPin() == progDriver->getFaultPin())
for (byte s=t+1;s<=lastTrack;s++) { // && (mainDriver->getFaultPin() != UNUSED_PIN));
if (track[t]->getFaultPin() != UNUSED_PIN && DCC::begin(shieldname);
track[t]->getFaultPin() == track[s]->getFaultPin()) {
track[t]->setCommonFaultPin();
track[s]->setCommonFaultPin();
DIAG(F("Common Fault pin tracks %c and %c"), t+'A', s+'A');
}
}
}
DCC::setShieldName(shieldname);
} }
void TrackManager::addTrack(byte t, MotorDriver* driver) { void TrackManager::addTrack(byte t, MotorDriver* driver) {
trackMode[t]=TRACK_MODE_OFF;
track[t]=driver; track[t]=driver;
if (driver) { if (driver) {
track[t]->setPower(POWERMODE::OFF); track[t]->setPower(POWERMODE::OFF);
track[t]->setMode(TRACK_MODE_NONE);
track[t]->setTrackLetter('A'+t); track[t]->setTrackLetter('A'+t);
lastTrack=t; lastTrack=t;
} }
@ -182,27 +169,22 @@ void TrackManager::setPROGSignal( bool on) {
// with interrupts turned off around the critical section // with interrupts turned off around the critical section
void TrackManager::setDCSignal(int16_t cab, byte speedbyte) { void TrackManager::setDCSignal(int16_t cab, byte speedbyte) {
FOR_EACH_TRACK(t) { FOR_EACH_TRACK(t) {
if (trackDCAddr[t]!=cab && cab != 0) continue; if (trackDCAddr[t]!=cab) continue;
if (track[t]->getMode()==TRACK_MODE_DC) track[t]->setDCSignal(speedbyte); if (trackMode[t]==TRACK_MODE_DC) track[t]->setDCSignal(speedbyte);
else if (track[t]->getMode()==TRACK_MODE_DCX) track[t]->setDCSignal(speedbyte ^ 128); else if (trackMode[t]==TRACK_MODE_DCX) track[t]->setDCSignal(speedbyte ^ 128);
} }
} }
bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr) { bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr) {
if (trackToSet>lastTrack || track[trackToSet]==NULL) return false; if (trackToSet>lastTrack || track[trackToSet]==NULL) return false;
//DIAG(F("Track=%c Mode=%d"),trackToSet+'A', mode); //DIAG(F("Track=%c"),trackToSet+'A');
// DC tracks require a motorDriver that can set brake! // DC tracks require a motorDriver that can set brake!
if (mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX) { if ((mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX)
#if defined(ARDUINO_AVR_UNO) && !track[trackToSet]->brakeCanPWM()) {
DIAG(F("Uno has no PWM timers available for DC"));
return false;
#endif
if (!track[trackToSet]->brakeCanPWM()) {
DIAG(F("Brake pin can't PWM: No DC")); DIAG(F("Brake pin can't PWM: No DC"));
return false; return false;
} }
}
#ifdef ARDUINO_ARCH_ESP32 #ifdef ARDUINO_ARCH_ESP32
// remove pin from MUX matrix and turn it off // remove pin from MUX matrix and turn it off
@ -216,16 +198,12 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
pinMode(p.invpin, OUTPUT); // gpio_reset_pin may reset to input pinMode(p.invpin, OUTPUT); // gpio_reset_pin may reset to input
} }
#endif #endif
#ifndef DISABLE_PROG
if (mode==TRACK_MODE_PROG) { if (mode==TRACK_MODE_PROG) {
#else
if (false) {
#endif
// only allow 1 track to be prog // only allow 1 track to be prog
FOR_EACH_TRACK(t) FOR_EACH_TRACK(t)
if (track[t]->getMode()==TRACK_MODE_PROG && t != trackToSet) { if (trackMode[t]==TRACK_MODE_PROG && t != trackToSet) {
track[t]->setPower(POWERMODE::OFF); track[t]->setPower(POWERMODE::OFF);
track[t]->setMode(TRACK_MODE_NONE); trackMode[t]=TRACK_MODE_OFF;
track[t]->makeProgTrack(false); // revoke prog track special handling track[t]->makeProgTrack(false); // revoke prog track special handling
streamTrackState(NULL,t); streamTrackState(NULL,t);
} }
@ -233,7 +211,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
} else { } else {
track[trackToSet]->makeProgTrack(false); // only the prog track knows it's type track[trackToSet]->makeProgTrack(false); // only the prog track knows it's type
} }
track[trackToSet]->setMode(mode); trackMode[trackToSet]=mode;
trackDCAddr[trackToSet]=dcAddr; trackDCAddr[trackToSet]=dcAddr;
streamTrackState(NULL,trackToSet); streamTrackState(NULL,trackToSet);
@ -260,7 +238,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
// DC tracks must not have the DCC PWM switched on // DC tracks must not have the DCC PWM switched on
// so we globally turn it off if one of the PWM // so we globally turn it off if one of the PWM
// capable tracks is now DC or DCX. // capable tracks is now DC or DCX.
if (track[t]->getMode()==TRACK_MODE_DC || track[t]->getMode()==TRACK_MODE_DCX) { if (trackMode[t]==TRACK_MODE_DC || trackMode[t]==TRACK_MODE_DCX) {
if (track[t]->isPWMCapable()) { if (track[t]->isPWMCapable()) {
canDo=false; // this track is capable but can not run PWM canDo=false; // this track is capable but can not run PWM
break; // in this mode, so abort and prevent globally below break; // in this mode, so abort and prevent globally below
@ -268,7 +246,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
track[t]->trackPWM=false; // this track sure can not run with PWM track[t]->trackPWM=false; // this track sure can not run with PWM
//DIAG(F("Track %c trackPWM 0 (not capable)"), t+'A'); //DIAG(F("Track %c trackPWM 0 (not capable)"), t+'A');
} }
} else if (track[t]->getMode()==TRACK_MODE_MAIN || track[t]->getMode()==TRACK_MODE_PROG) { } else if (trackMode[t]==TRACK_MODE_MAIN || trackMode[t]==TRACK_MODE_PROG) {
track[t]->trackPWM = track[t]->isPWMCapable(); // trackPWM is still a guess here track[t]->trackPWM = track[t]->isPWMCapable(); // trackPWM is still a guess here
//DIAG(F("Track %c trackPWM %d"), t+'A', track[t]->trackPWM); //DIAG(F("Track %c trackPWM %d"), t+'A', track[t]->trackPWM);
canDo &= track[t]->trackPWM; canDo &= track[t]->trackPWM;
@ -306,7 +284,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
void TrackManager::applyDCSpeed(byte t) { void TrackManager::applyDCSpeed(byte t) {
uint8_t speedByte=DCC::getThrottleSpeedByte(trackDCAddr[t]); uint8_t speedByte=DCC::getThrottleSpeedByte(trackDCAddr[t]);
if (track[t]->getMode()==TRACK_MODE_DCX) if (trackMode[t]==TRACK_MODE_DCX)
speedByte = speedByte ^ 128; // reverse direction bit speedByte = speedByte ^ 128; // reverse direction bit
track[t]->setDCSignal(speedByte); track[t]->setDCSignal(speedByte);
} }
@ -328,13 +306,11 @@ bool TrackManager::parseJ(Print *stream, int16_t params, int16_t p[])
if (params==2 && p[1]==HASH_KEYWORD_MAIN) // <= id MAIN> if (params==2 && p[1]==HASH_KEYWORD_MAIN) // <= id MAIN>
return setTrackMode(p[0],TRACK_MODE_MAIN); return setTrackMode(p[0],TRACK_MODE_MAIN);
#ifndef DISABLE_PROG
if (params==2 && p[1]==HASH_KEYWORD_PROG) // <= id PROG> if (params==2 && p[1]==HASH_KEYWORD_PROG) // <= id PROG>
return setTrackMode(p[0],TRACK_MODE_PROG); return setTrackMode(p[0],TRACK_MODE_PROG);
#endif
if (params==2 && (p[1]==HASH_KEYWORD_OFF || p[1]==HASH_KEYWORD_NONE)) // <= id OFF> <= id NONE> if (params==2 && p[1]==HASH_KEYWORD_OFF) // <= id OFF>
return setTrackMode(p[0],TRACK_MODE_NONE); return setTrackMode(p[0],TRACK_MODE_OFF);
if (params==2 && p[1]==HASH_KEYWORD_EXT) // <= id EXT> if (params==2 && p[1]==HASH_KEYWORD_EXT) // <= id EXT>
return setTrackMode(p[0],TRACK_MODE_EXT); return setTrackMode(p[0],TRACK_MODE_EXT);
@ -352,17 +328,15 @@ void TrackManager::streamTrackState(Print* stream, byte t) {
// null stream means send to commandDistributor for broadcast // null stream means send to commandDistributor for broadcast
if (track[t]==NULL) return; if (track[t]==NULL) return;
auto format=F(""); auto format=F("");
switch(track[t]->getMode()) { switch(trackMode[t]) {
case TRACK_MODE_MAIN: case TRACK_MODE_MAIN:
format=F("<= %c MAIN>\n"); format=F("<= %c MAIN>\n");
break; break;
#ifndef DISABLE_PROG
case TRACK_MODE_PROG: case TRACK_MODE_PROG:
format=F("<= %c PROG>\n"); format=F("<= %c PROG>\n");
break; break;
#endif case TRACK_MODE_OFF:
case TRACK_MODE_NONE: format=F("<= %c OFF>\n");
format=F("<= %c NONE>\n");
break; break;
case TRACK_MODE_EXT: case TRACK_MODE_EXT:
format=F("<= %c EXT>\n"); format=F("<= %c EXT>\n");
@ -384,21 +358,19 @@ byte TrackManager::nextCycleTrack=MAX_TRACKS;
void TrackManager::loop() { void TrackManager::loop() {
DCCWaveform::loop(); DCCWaveform::loop();
#ifndef DISABLE_PROG
DCCACK::loop(); DCCACK::loop();
#endif
bool dontLimitProg=DCCACK::isActive() || progTrackSyncMain || progTrackBoosted; bool dontLimitProg=DCCACK::isActive() || progTrackSyncMain || progTrackBoosted;
nextCycleTrack++; nextCycleTrack++;
if (nextCycleTrack>lastTrack) nextCycleTrack=0; if (nextCycleTrack>lastTrack) nextCycleTrack=0;
if (track[nextCycleTrack]==NULL) return; if (track[nextCycleTrack]==NULL) return;
MotorDriver * motorDriver=track[nextCycleTrack]; MotorDriver * motorDriver=track[nextCycleTrack];
bool useProgLimit=dontLimitProg? false: track[nextCycleTrack]->getMode()==TRACK_MODE_PROG; bool useProgLimit=dontLimitProg? false: trackMode[nextCycleTrack]==TRACK_MODE_PROG;
motorDriver->checkPowerOverload(useProgLimit, nextCycleTrack); motorDriver->checkPowerOverload(useProgLimit, nextCycleTrack);
} }
MotorDriver * TrackManager::getProgDriver() { MotorDriver * TrackManager::getProgDriver() {
FOR_EACH_TRACK(t) FOR_EACH_TRACK(t)
if (track[t]->getMode()==TRACK_MODE_PROG) return track[t]; if (trackMode[t]==TRACK_MODE_PROG) return track[t];
return NULL; return NULL;
} }
@ -406,7 +378,7 @@ MotorDriver * TrackManager::getProgDriver() {
std::vector<MotorDriver *>TrackManager::getMainDrivers() { std::vector<MotorDriver *>TrackManager::getMainDrivers() {
std::vector<MotorDriver *> v; std::vector<MotorDriver *> v;
FOR_EACH_TRACK(t) FOR_EACH_TRACK(t)
if (track[t]->getMode()==TRACK_MODE_MAIN) v.push_back(track[t]); if (trackMode[t]==TRACK_MODE_MAIN) v.push_back(track[t]);
return v; return v;
} }
#endif #endif
@ -416,7 +388,7 @@ void TrackManager::setPower2(bool setProg,POWERMODE mode) {
FOR_EACH_TRACK(t) { FOR_EACH_TRACK(t) {
MotorDriver * driver=track[t]; MotorDriver * driver=track[t];
if (!driver) continue; if (!driver) continue;
switch (track[t]->getMode()) { switch (trackMode[t]) {
case TRACK_MODE_MAIN: case TRACK_MODE_MAIN:
if (setProg) break; if (setProg) break;
// toggle brake before turning power on - resets overcurrent error // toggle brake before turning power on - resets overcurrent error
@ -444,7 +416,7 @@ void TrackManager::setPower2(bool setProg,POWERMODE mode) {
driver->setBrake(false); driver->setBrake(false);
driver->setPower(mode); driver->setPower(mode);
break; break;
case TRACK_MODE_NONE: case TRACK_MODE_OFF:
break; break;
} }
} }
@ -452,7 +424,7 @@ void TrackManager::setPower2(bool setProg,POWERMODE mode) {
POWERMODE TrackManager::getProgPower() { POWERMODE TrackManager::getProgPower() {
FOR_EACH_TRACK(t) FOR_EACH_TRACK(t)
if (track[t]->getMode()==TRACK_MODE_PROG) if (trackMode[t]==TRACK_MODE_PROG)
return track[t]->getPower(); return track[t]->getPower();
return POWERMODE::OFF; return POWERMODE::OFF;
} }
@ -497,7 +469,7 @@ void TrackManager::setJoin(bool joined) {
#ifdef ARDUINO_ARCH_ESP32 #ifdef ARDUINO_ARCH_ESP32
if (joined) { if (joined) {
FOR_EACH_TRACK(t) { FOR_EACH_TRACK(t) {
if (track[t]->getMode()==TRACK_MODE_PROG) { if (trackMode[t]==TRACK_MODE_PROG) {
tempProgTrack = t; tempProgTrack = t;
setTrackMode(t, TRACK_MODE_MAIN); setTrackMode(t, TRACK_MODE_MAIN);
break; break;

View File

@ -27,6 +27,10 @@
#include "MotorDriver.h" #include "MotorDriver.h"
// Virtualised Motor shield multi-track hardware Interface // Virtualised Motor shield multi-track hardware Interface
// use powers of two so we can do logical and/or on the track modes in if clauses.
enum TRACK_MODE : byte {TRACK_MODE_OFF = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PROG = 4,
TRACK_MODE_DC = 8, TRACK_MODE_DCX = 16, TRACK_MODE_EXT = 32};
// These constants help EXRAIL macros say SET_TRACK(2,mode) OR SET_TRACK(C,mode) etc. // These constants help EXRAIL macros say SET_TRACK(2,mode) OR SET_TRACK(C,mode) etc.
const byte TRACK_NUMBER_0=0, TRACK_NUMBER_A=0; const byte TRACK_NUMBER_0=0, TRACK_NUMBER_A=0;
const byte TRACK_NUMBER_1=1, TRACK_NUMBER_B=1; const byte TRACK_NUMBER_1=1, TRACK_NUMBER_B=1;
@ -82,13 +86,6 @@ class TrackManager {
static bool progTrackSyncMain; // true when prog track is a siding switched to main static bool progTrackSyncMain; // true when prog track is a siding switched to main
static bool progTrackBoosted; // true when prog track is not current limited static bool progTrackBoosted; // true when prog track is not current limited
#ifdef DEBUG_ADC
public:
#else
private:
#endif
static MotorDriver* track[MAX_TRACKS];
private: private:
static void addTrack(byte t, MotorDriver* driver); static void addTrack(byte t, MotorDriver* driver);
static byte lastTrack; static byte lastTrack;
@ -96,6 +93,8 @@ class TrackManager {
static POWERMODE mainPowerGuess; static POWERMODE mainPowerGuess;
static void applyDCSpeed(byte t); static void applyDCSpeed(byte t);
static MotorDriver* track[MAX_TRACKS];
static TRACK_MODE trackMode[MAX_TRACKS];
static int16_t trackDCAddr[MAX_TRACKS]; // dc address if TRACK_MODE_DC or TRACK_MODE_DCX static int16_t trackDCAddr[MAX_TRACKS]; // dc address if TRACK_MODE_DC or TRACK_MODE_DCX
#ifdef ARDUINO_ARCH_ESP32 #ifdef ARDUINO_ARCH_ESP32
static byte tempProgTrack; // holds the prog track number during join static byte tempProgTrack; // holds the prog track number during join

View File

@ -250,7 +250,6 @@
} }
} }
tt = (Turnout *)new ServoTurnout(id, vpin, thrownPosition, closedPosition, profile, closed); tt = (Turnout *)new ServoTurnout(id, vpin, thrownPosition, closedPosition, profile, closed);
DIAG(F("Turnout 0x%x size %d size %d"), tt, sizeof(Turnout),sizeof(struct TurnoutData));
IODevice::writeAnalogue(vpin, closed ? closedPosition : thrownPosition, PCA9685::Instant); IODevice::writeAnalogue(vpin, closed ? closedPosition : thrownPosition, PCA9685::Instant);
return tt; return tt;
#else #else

View File

@ -69,12 +69,10 @@ protected:
uint16_t id; uint16_t id;
} _turnoutData; // 3 bytes } _turnoutData; // 3 bytes
#ifndef DISABLE_EEPROM
// Address in eeprom of first byte of the _turnoutData struct (containing the closed flag). // Address in eeprom of first byte of the _turnoutData struct (containing the closed flag).
// Set to zero if the object has not been saved in EEPROM, e.g. for newly created Turnouts, and // Set to zero if the object has not been saved in EEPROM, e.g. for newly created Turnouts, and
// for all LCN turnouts. // for all LCN turnouts.
uint16_t _eepromAddress = 0; uint16_t _eepromAddress = 0;
#endif
// Pointer to next turnout on linked list. // Pointer to next turnout on linked list.
Turnout *_nextTurnout = 0; Turnout *_nextTurnout = 0;

View File

@ -235,10 +235,6 @@ int WiThrottle::getLocoId(byte * cmd) {
void WiThrottle::multithrottle(RingStream * stream, byte * cmd){ void WiThrottle::multithrottle(RingStream * stream, byte * cmd){
char throttleChar=cmd[1]; char throttleChar=cmd[1];
int locoid=getLocoId(cmd+3); // -1 for * int locoid=getLocoId(cmd+3); // -1 for *
if (locoid > 10239 || locoid < -1) {
StringFormatter::send(stream, F("No valid DCC loco %d\n"), locoid);
return;
}
byte * aval=cmd; byte * aval=cmd;
while(*aval !=';' && *aval !='\0') aval++; while(*aval !=';' && *aval !='\0') aval++;
if (*aval) aval+=2; // skip ;> if (*aval) aval+=2; // skip ;>
@ -531,11 +527,8 @@ void WiThrottle::sendRoster(Print* stream) {
rosterSent=true; rosterSent=true;
#ifdef EXRAIL_ACTIVE #ifdef EXRAIL_ACTIVE
StringFormatter::send(stream,F("RL%d"), RMFT2::rosterNameCount); StringFormatter::send(stream,F("RL%d"), RMFT2::rosterNameCount);
for (int16_t r=0;;r++) { for (int16_t r=0;r<RMFT2::rosterNameCount;r++) {
int16_t cabid=GETHIGHFLASHW(RMFT2::rosterIdList,r*2); int16_t cabid=GETHIGHFLASHW(RMFT2::rosterIdList,r*2);
if (cabid == INT16_MAX)
break;
if (cabid > 0)
StringFormatter::send(stream,F("]\\[%S}|{%d}|{%c"), StringFormatter::send(stream,F("]\\[%S}|{%d}|{%c"),
RMFT2::getRosterName(cabid),cabid,cabid<128?'S':'L'); RMFT2::getRosterName(cabid),cabid,cabid<128?'S':'L');
} }
@ -551,14 +544,14 @@ void WiThrottle::sendRoutes(Print* stream) {
// first pass automations // first pass automations
for (int ix=0;;ix+=2) { for (int ix=0;;ix+=2) {
int16_t id =GETHIGHFLASHW(RMFT2::automationIdList,ix); int16_t id =GETHIGHFLASHW(RMFT2::automationIdList,ix);
if (id==INT16_MAX) break; if (id==0) break;
const FSH * desc=RMFT2::getRouteDescription(id); const FSH * desc=RMFT2::getRouteDescription(id);
StringFormatter::send(stream,F("]\\[A%d}|{%S}|{4"),id,desc); StringFormatter::send(stream,F("]\\[A%d}|{%S}|{4"),id,desc);
} }
// second pass routes. // second pass routes.
for (int ix=0;;ix+=2) { for (int ix=0;;ix+=2) {
int16_t id=GETHIGHFLASHW(RMFT2::routeIdList,ix); int16_t id=GETHIGHFLASHW(RMFT2::routeIdList,ix);
if (id==INT16_MAX) break; if (id==0) break;
const FSH * desc=RMFT2::getRouteDescription(id); const FSH * desc=RMFT2::getRouteDescription(id);
StringFormatter::send(stream,F("]\\[R%d}|{%S}|{2"),id,desc); StringFormatter::send(stream,F("]\\[R%d}|{%S}|{2"),id,desc);
} }
@ -574,13 +567,9 @@ void WiThrottle::sendFunctions(Print* stream, byte loco) {
myLocos[loco].functionToggles=1<<2; // F2 (HORN) is a non-toggle myLocos[loco].functionToggles=1<<2; // F2 (HORN) is a non-toggle
#ifdef EXRAIL_ACTIVE #ifdef EXRAIL_ACTIVE
const FSH * functionNames= RMFT2::getRosterFunctions(locoid); const char * functionNames=(char *) RMFT2::getRosterFunctions(locoid);
if (functionNames == NULL) { if (!functionNames) {
// no roster entry for locoid, try to find default entry // no roster, use non-exrail presets as above
functionNames= RMFT2::getRosterFunctions(0);
}
if (functionNames == NULL) {
// no default roster entry either, use non-exrail presets as above
} }
else if (GETFLASH(functionNames)=='\0') { else if (GETFLASH(functionNames)=='\0') {
// "" = Roster but no functions given // "" = Roster but no functions given
@ -595,7 +584,7 @@ void WiThrottle::sendFunctions(Print* stream, byte loco) {
fkeys=0; fkeys=0;
bool firstchar=true; bool firstchar=true;
for (int fx=0;;fx++) { for (int fx=0;;fx++) {
char c=GETFLASH((char *)functionNames+fx); char c=GETFLASH(functionNames+fx);
if (c=='\0') { if (c=='\0') {
fkeys++; fkeys++;
break; break;

View File

@ -1,7 +1,5 @@
/* /*
© 2023 Paul M. Antoine © 2021, Harald Barth.
© 2021 Harald Barth
© 2023 Nathan Kellenicki
This file is part of CommandStation-EX This file is part of CommandStation-EX
@ -22,7 +20,6 @@
#if defined(ARDUINO_ARCH_ESP32) #if defined(ARDUINO_ARCH_ESP32)
#include <vector> #include <vector>
#include "defines.h" #include "defines.h"
#include "ESPmDNS.h"
#include <WiFi.h> #include <WiFi.h>
#include "esp_wifi.h" #include "esp_wifi.h"
#include "WifiESP32.h" #include "WifiESP32.h"
@ -108,18 +105,11 @@ void wifiLoop(void *){
} }
#endif #endif
char asciitolower(char in) {
if (in <= 'Z' && in >= 'A')
return in - ('Z' - 'z');
return in;
}
bool WifiESP::setup(const char *SSid, bool WifiESP::setup(const char *SSid,
const char *password, const char *password,
const char *hostname, const char *hostname,
int port, int port,
const byte channel, const byte channel) {
const bool forceAP) {
bool havePassword = true; bool havePassword = true;
bool haveSSID = true; bool haveSSID = true;
bool wifiUp = false; bool wifiUp = false;
@ -147,8 +137,7 @@ bool WifiESP::setup(const char *SSid,
if (strncmp(yourNetwork, password, 13) == 0 || strncmp("", password, 13) == 0) if (strncmp(yourNetwork, password, 13) == 0 || strncmp("", password, 13) == 0)
havePassword = false; havePassword = false;
if (haveSSID && havePassword && !forceAP) { if (haveSSID && havePassword) {
WiFi.setHostname(hostname); // Strangely does not work unless we do it HERE!
WiFi.mode(WIFI_STA); WiFi.mode(WIFI_STA);
#ifdef SERIAL_BT_COMMANDS #ifdef SERIAL_BT_COMMANDS
WiFi.setSleep(true); WiFi.setSleep(true);
@ -185,20 +174,16 @@ bool WifiESP::setup(const char *SSid,
} }
} }
} }
if (!haveSSID || forceAP) { if (!haveSSID) {
// prepare all strings // prepare all strings
String strSSID(forceAP ? SSid : "DCCEX_"); String strSSID("DCC_");
String strPass(forceAP ? password : "PASS_"); String strPass("PASS_");
if (!forceAP) {
String strMac = WiFi.macAddress(); String strMac = WiFi.macAddress();
strMac.remove(0,9); strMac.remove(0,9);
strMac.replace(":",""); strMac.replace(":","");
strMac.replace(":",""); strMac.replace(":","");
// convert mac addr hex chars to lower case to be compatible with AT software
std::transform(strMac.begin(), strMac.end(), strMac.begin(), asciitolower);
strSSID.concat(strMac); strSSID.concat(strMac);
strPass.concat(strMac); strPass.concat(strMac);
}
WiFi.mode(WIFI_AP); WiFi.mode(WIFI_AP);
#ifdef SERIAL_BT_COMMANDS #ifdef SERIAL_BT_COMMANDS
@ -224,15 +209,6 @@ bool WifiESP::setup(const char *SSid,
// no idea to go on // no idea to go on
return false; return false;
} }
// Now Wifi is up, register the mDNS service
if(!MDNS.begin(hostname)) {
DIAG(F("Wifi setup failed to start mDNS"));
}
if(!MDNS.addService("withrottle", "tcp", 2560)) {
DIAG(F("Wifi setup failed to add withrottle service to mDNS"));
}
server = new WiFiServer(port); // start listening on tcp port server = new WiFiServer(port); // start listening on tcp port
server->begin(); server->begin();
// server started here // server started here

View File

@ -1,6 +1,5 @@
/* /*
* © 2021 Harald Barth * © 2021, Harald Barth.
* © 2023 Nathan Kellenicki
* *
* This file is part of CommandStation-EX * This file is part of CommandStation-EX
* *
@ -32,8 +31,7 @@ public:
const char *wifiPassword, const char *wifiPassword,
const char *hostname, const char *hostname,
const int port, const int port,
const byte channel, const byte channel);
const bool forceAP);
static void loop(); static void loop();
private: private:
}; };

View File

@ -2,7 +2,6 @@
* © 2021 Fred Decker * © 2021 Fred Decker
* © 2020-2022 Harald Barth * © 2020-2022 Harald Barth
* © 2020-2022 Chris Harlow * © 2020-2022 Chris Harlow
* © 2023 Nathan Kellenicki
* All rights reserved. * All rights reserved.
* *
* This file is part of CommandStation-EX * This file is part of CommandStation-EX
@ -53,32 +52,10 @@ Stream * WifiInterface::wifiStream;
#if (defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)) #if (defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560))
#define NUM_SERIAL 3 #define NUM_SERIAL 3
#define SERIAL1 Serial1
#define SERIAL3 Serial3
#endif
#if defined(ARDUINO_ARCH_STM32)
// Handle serial ports availability on STM32 for variants!
// #undef NUM_SERIAL
#if defined(ARDUINO_NUCLEO_F401RE) || defined(ARDUINO_NUCLEO_F411RE)
#define NUM_SERIAL 3
#define SERIAL1 Serial1
#define SERIAL3 Serial6
#elif defined(ARDUINO_NUCLEO_F446RE)
#define NUM_SERIAL 3
#define SERIAL1 Serial3
#define SERIAL3 Serial5
#elif defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) || defined(ARDUINO_NUCLEO_F412ZG)
#define NUM_SERIAL 2
#define SERIAL1 Serial6
#else
#warning This variant of Nucleo not yet explicitly supported
#endif
#endif #endif
#ifndef NUM_SERIAL #ifndef NUM_SERIAL
#define NUM_SERIAL 1 #define NUM_SERIAL 1
#define SERIAL1 Serial1
#endif #endif
bool WifiInterface::setup(long serial_link_speed, bool WifiInterface::setup(long serial_link_speed,
@ -86,8 +63,7 @@ bool WifiInterface::setup(long serial_link_speed,
const FSH *wifiPassword, const FSH *wifiPassword,
const FSH *hostname, const FSH *hostname,
const int port, const int port,
const byte channel, const byte channel) {
const bool forceAP) {
wifiSerialState wifiUp = WIFI_NOAT; wifiSerialState wifiUp = WIFI_NOAT;
@ -99,34 +75,27 @@ bool WifiInterface::setup(long serial_link_speed,
(void) hostname; (void) hostname;
(void) port; (void) port;
(void) channel; (void) channel;
(void) forceAP;
#endif #endif
// See if the WiFi is attached to the first serial port
#if NUM_SERIAL > 0 && !defined(SERIAL1_COMMANDS) #if NUM_SERIAL > 0 && !defined(SERIAL1_COMMANDS)
SERIAL1.begin(serial_link_speed); Serial1.begin(serial_link_speed);
wifiUp = setup(SERIAL1, wifiESSID, wifiPassword, hostname, port, channel, forceAP); wifiUp = setup(Serial1, wifiESSID, wifiPassword, hostname, port, channel);
#endif #endif
// Other serials are tried, depending on hardware. // Other serials are tried, depending on hardware.
// Currently only the Arduino Mega 2560 has usable Serial2 (Nucleo-64 boards use Serial 2 for console!)
#if defined(ARDUINO_AVR_MEGA2560)
#if NUM_SERIAL > 1 && !defined(SERIAL2_COMMANDS) #if NUM_SERIAL > 1 && !defined(SERIAL2_COMMANDS)
if (wifiUp == WIFI_NOAT) if (wifiUp == WIFI_NOAT)
{ {
Serial2.begin(serial_link_speed); Serial2.begin(serial_link_speed);
wifiUp = setup(Serial2, wifiESSID, wifiPassword, hostname, port, channel, forceAP); wifiUp = setup(Serial2, wifiESSID, wifiPassword, hostname, port, channel);
} }
#endif #endif
#endif
// We guess here that in all architctures that have a Serial3
// we can use it for our purpose.
#if NUM_SERIAL > 2 && !defined(SERIAL3_COMMANDS) #if NUM_SERIAL > 2 && !defined(SERIAL3_COMMANDS)
if (wifiUp == WIFI_NOAT) if (wifiUp == WIFI_NOAT)
{ {
SERIAL3.begin(serial_link_speed); Serial3.begin(serial_link_speed);
wifiUp = setup(SERIAL3, wifiESSID, wifiPassword, hostname, port, channel, forceAP); wifiUp = setup(Serial3, wifiESSID, wifiPassword, hostname, port, channel);
} }
#endif #endif
@ -144,7 +113,7 @@ bool WifiInterface::setup(long serial_link_speed,
} }
wifiSerialState WifiInterface::setup(Stream & setupStream, const FSH* SSid, const FSH* password, wifiSerialState WifiInterface::setup(Stream & setupStream, const FSH* SSid, const FSH* password,
const FSH* hostname, int port, byte channel, bool forceAP) { const FSH* hostname, int port, byte channel) {
wifiSerialState wifiState; wifiSerialState wifiState;
static uint8_t ntry = 0; static uint8_t ntry = 0;
ntry++; ntry++;
@ -153,7 +122,7 @@ wifiSerialState WifiInterface::setup(Stream & setupStream, const FSH* SSid, con
DIAG(F("++ Wifi Setup Try %d ++"), ntry); DIAG(F("++ Wifi Setup Try %d ++"), ntry);
wifiState = setup2( SSid, password, hostname, port, channel, forceAP); wifiState = setup2( SSid, password, hostname, port, channel);
if (wifiState == WIFI_NOAT) { if (wifiState == WIFI_NOAT) {
LCD(4, F("WiFi no AT chip")); LCD(4, F("WiFi no AT chip"));
@ -177,7 +146,7 @@ wifiSerialState WifiInterface::setup(Stream & setupStream, const FSH* SSid, con
#pragma GCC diagnostic ignored "-Wunused-parameter" #pragma GCC diagnostic ignored "-Wunused-parameter"
#endif #endif
wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password, wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password,
const FSH* hostname, int port, byte channel, bool forceAP) { const FSH* hostname, int port, byte channel) {
bool ipOK = false; bool ipOK = false;
bool oldCmd = false; bool oldCmd = false;
@ -200,21 +169,7 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password,
// Display the AT version information // Display the AT version information
StringFormatter::send(wifiStream, F("AT+GMR\r\n")); StringFormatter::send(wifiStream, F("AT+GMR\r\n"));
if (checkForOK(2000, F("AT version:"), true, false)) { checkForOK(2000, true, false); // Makes this visible on the console
char version[] = "0.0.0.0";
for (int i=0; i<8;i++) {
while(!wifiStream->available());
version[i]=wifiStream->read();
StringFormatter::printEscape(version[i]);
if ((version[0] == '0') ||
(version[0] == '2' && version[2] == '0') ||
(version[0] == '2' && version[2] == '2' && version[4] == '0' && version[6] == '0')) {
SSid = F("DCCEX_SAYS_BROKEN_FIRMWARE");
forceAP = true;
}
}
}
checkForOK(2000, true, false);
#ifdef DONT_TOUCH_WIFI_CONF #ifdef DONT_TOUCH_WIFI_CONF
DIAG(F("DONT_TOUCH_WIFI_CONF was set: Using existing config")); DIAG(F("DONT_TOUCH_WIFI_CONF was set: Using existing config"));
@ -244,7 +199,7 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password,
if (!checkForOK(1000, F("0.0.0.0"), true,false)) if (!checkForOK(1000, F("0.0.0.0"), true,false))
ipOK = true; ipOK = true;
} }
} else if (!forceAP) { } else {
// SSID was configured, so we assume station (client) mode. // SSID was configured, so we assume station (client) mode.
if (oldCmd) { if (oldCmd) {
// AT command early version supports CWJAP/CWSAP // AT command early version supports CWJAP/CWSAP
@ -304,7 +259,6 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password,
i=0; i=0;
do { do {
if (!forceAP) {
if (STRNCMP_P(yourNetwork, (const char*)password, 13) == 0) { if (STRNCMP_P(yourNetwork, (const char*)password, 13) == 0) {
// unconfigured // unconfigured
StringFormatter::send(wifiStream, F("AT+CWSAP%s=\"DCCEX_%s\",\"PASS_%s\",%d,4\r\n"), StringFormatter::send(wifiStream, F("AT+CWSAP%s=\"DCCEX_%s\",\"PASS_%s\",%d,4\r\n"),
@ -314,10 +268,6 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password,
StringFormatter::send(wifiStream, F("AT+CWSAP%s=\"DCCEX_%s\",\"%S\",%d,4\r\n"), oldCmd ? "" : "_CUR", StringFormatter::send(wifiStream, F("AT+CWSAP%s=\"DCCEX_%s\",\"%S\",%d,4\r\n"), oldCmd ? "" : "_CUR",
macTail, password, channel); macTail, password, channel);
} }
} else {
StringFormatter::send(wifiStream, F("AT+CWSAP%s=\"%S\",\"%S\",%d,4\r\n"),
oldCmd ? "" : "_CUR", SSid, password, channel);
}
} while (!checkForOK(WIFI_CONNECT_TIMEOUT, true) && i++<2); // do twice if necessary but ignore failure as AP mode may still be ok } while (!checkForOK(WIFI_CONNECT_TIMEOUT, true) && i++<2); // do twice if necessary but ignore failure as AP mode may still be ok
if (i >= 2) if (i >= 2)
DIAG(F("Warning: Setting AP SSID and password failed")); // but issue warning DIAG(F("Warning: Setting AP SSID and password failed")); // but issue warning

View File

@ -1,7 +1,6 @@
/* /*
* © 2020-2021 Chris Harlow * © 2020-2021 Chris Harlow
* © 2020, Harald Barth. * © 2020, Harald Barth.
* © 2023 Nathan Kellenicki
* All rights reserved. * All rights reserved.
* *
* This file is part of CommandStation-EX * This file is part of CommandStation-EX
@ -37,18 +36,17 @@ public:
const FSH *wifiPassword, const FSH *wifiPassword,
const FSH *hostname, const FSH *hostname,
const int port, const int port,
const byte channel, const byte channel);
const bool forceAP);
static void loop(); static void loop();
static void ATCommand(HardwareSerial * stream,const byte *command); static void ATCommand(HardwareSerial * stream,const byte *command);
private: private:
static wifiSerialState setup(Stream &setupStream, const FSH *SSSid, const FSH *password, static wifiSerialState setup(Stream &setupStream, const FSH *SSSid, const FSH *password,
const FSH *hostname, int port, byte channel, bool forceAP); const FSH *hostname, int port, byte channel);
static Stream *wifiStream; static Stream *wifiStream;
static DCCEXParser parser; static DCCEXParser parser;
static wifiSerialState setup2(const FSH *SSSid, const FSH *password, static wifiSerialState setup2(const FSH *SSSid, const FSH *password,
const FSH *hostname, int port, byte channel, bool forceAP); const FSH *hostname, int port, byte channel);
static bool checkForOK(const unsigned int timeout, bool echo, bool escapeEcho = true); static bool checkForOK(const unsigned int timeout, bool echo, bool escapeEcho = true);
static bool checkForOK(const unsigned int timeout, const FSH *waitfor, bool echo, bool escapeEcho = true); static bool checkForOK(const unsigned int timeout, const FSH *waitfor, bool echo, bool escapeEcho = true);
static bool connected; static bool connected;

View File

@ -1,10 +1,9 @@
/* /*
* © 2022 Paul M. Antoine * © 2022 Paul M. Antoine
* © 2021 Neil McKechnie * © 2021 Neil McKechnie
* © 2020-2023 Harald Barth * © 2020-2021 Harald Barth
* © 2020-2021 Fred Decker * © 2020-2021 Fred Decker
* © 2020-2021 Chris Harlow * © 2020-2021 Chris Harlow
* © 2023 Nathan Kellenicki
* *
* This file is part of CommandStation-EX * This file is part of CommandStation-EX
* *
@ -28,16 +27,6 @@ The configuration file for DCC-EX Command Station
**********************************************************************/ **********************************************************************/
/////////////////////////////////////////////////////////////////////////////////////
// If you want to add your own motor driver definition(s), add them here
// For example MY_SHIELD with display name "MINE":
// (remove comment start and end marker if you want to edit and use that)
/*
#define MY_SHIELD F("MINE"), \
new MotorDriver( 3, 12, UNUSED_PIN, 9, A0, 5.08, 3000, A4), \
new MotorDriver(11, 13, UNUSED_PIN, 8, A1, 5.08, 1500, A5)
*/
///////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////
// NOTE: Before connecting these boards and selecting one in this software // NOTE: Before connecting these boards and selecting one in this software
// check the quick install guides!!! Some of these boards require a voltage // check the quick install guides!!! Some of these boards require a voltage
@ -45,34 +34,19 @@ The configuration file for DCC-EX Command Station
// the correct resistor could damage the sense pin on your Arduino or destroy // the correct resistor could damage the sense pin on your Arduino or destroy
// the device. // the device.
// //
// DEFINE MOTOR_SHIELD_TYPE BELOW. THESE ARE EXAMPLES. FULL LIST IN MotorDrivers.h // DEFINE MOTOR_SHIELD_TYPE BELOW ACCORDING TO THE FOLLOWING TABLE:
// //
// STANDARD_MOTOR_SHIELD : Arduino Motor shield Rev3 based on the L298 with 18V 2A per channel // STANDARD_MOTOR_SHIELD : Arduino Motor shield Rev3 based on the L298 with 18V 2A per channel
// POLOLU_MOTOR_SHIELD : Pololu MC33926 Motor Driver (not recommended for prog track) // POLOLU_MOTOR_SHIELD : Pololu MC33926 Motor Driver (not recommended for prog track)
// POLOLU_TB9051FTG : Pololu Dual TB9051FTG Motor Driver
// FUNDUMOTO_SHIELD : Fundumoto Shield, no current sensing (not recommended, no short protection) // FUNDUMOTO_SHIELD : Fundumoto Shield, no current sensing (not recommended, no short protection)
// FIREBOX_MK1 : The Firebox MK1 // FIREBOX_MK1 : The Firebox MK1
// FIREBOX_MK1S : The Firebox MK1S // FIREBOX_MK1S : The Firebox MK1S
// IBT_2_WITH_ARDUINO : Arduino Motor Shield for PROG and IBT-2 for MAIN // IBT_2_WITH_ARDUINO : Arduino Motor Shield for PROG and IBT-2 for MAIN
// EX8874_SHIELD : DCC-EX TI DRV8874 based motor shield
// | // |
// +-----------------------v // +-----------------------v
// //
#define MOTOR_SHIELD_TYPE STANDARD_MOTOR_SHIELD #define MOTOR_SHIELD_TYPE STANDARD_MOTOR_SHIELD
//
/////////////////////////////////////////////////////////////////////////////////////
//
// If you want to restrict the maximum current LOWER than what your
// motor shield can provide, you can do that here. For example if you
// have a motor shield that can provide 5A and your power supply can
// only provide 2.5A then you should restict the maximum current to
// 2.25A (90% of 2.5A) so that DCC-EX does shut off the track before
// your PS does shut DCC-EX. MAX_CURRENT is in mA so for this example
// it would be 2250, adjust the number according to your PS. If your
// PS has a higher rating than your motor shield you do not need this.
// You can use this as well if you are cautious and your trains do not
// need full current.
// #define MAX_CURRENT 2250
//
///////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////
// //
// The IP port to talk to a WIFI or Ethernet shield. // The IP port to talk to a WIFI or Ethernet shield.
@ -124,11 +98,6 @@ The configuration file for DCC-EX Command Station
// this line exists or not. If you need to use an alternate channel (we recommend // this line exists or not. If you need to use an alternate channel (we recommend
// using only 1,6, or 11) you may change it here. // using only 1,6, or 11) you may change it here.
#define WIFI_CHANNEL 1 #define WIFI_CHANNEL 1
//
// WIFI_FORCE_AP: If you'd like to specify your own WIFI_SSID in AP mode, set this
// true. Otherwise it is assumed that you'd like to connect to an existing network
// with that SSID.
#define WIFI_FORCE_AP false
///////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////
// //
@ -159,7 +128,7 @@ The configuration file for DCC-EX Command Station
//OR define OLED_DRIVER width,height[,address] in pixels (address auto detected if not supplied) //OR define OLED_DRIVER width,height[,address] in pixels (address auto detected if not supplied)
// 128x32 or 128x64 I2C SSD1306-based devices are supported. // 128x32 or 128x64 I2C SSD1306-based devices are supported.
// Use 132,64 for a SH1106-based I2C device with a 128x64 display. // Use 132,64 for a SH1106-based I2C device with a 128x64 display.
// #define OLED_DRIVER 0x3c,128,32 // #define OLED_DRIVER 128,32,0x3c
// Define scroll mode as 0, 1 or 2 // Define scroll mode as 0, 1 or 2
// * #define SCROLLMODE 0 is scroll continuous (fill screen if poss), // * #define SCROLLMODE 0 is scroll continuous (fill screen if poss),
@ -172,7 +141,7 @@ The configuration file for DCC-EX Command Station
// //
// If you do not need the EEPROM at all, you can disable all the code that saves // If you do not need the EEPROM at all, you can disable all the code that saves
// data in the EEPROM. You might want to do that if you are in a Arduino UNO // data in the EEPROM. You might want to do that if you are in a Arduino UNO
// and want to use the EXRAIL automation. Otherwise you do not have enough RAM // and want to use the EX-RAIL automation. Otherwise you do not have enough RAM
// to do that. Of course, then none of the EEPROM related commands work. // to do that. Of course, then none of the EEPROM related commands work.
// //
// EEPROM does not work on ESP32. So on ESP32, EEPROM will always be disabled, // EEPROM does not work on ESP32. So on ESP32, EEPROM will always be disabled,
@ -180,17 +149,6 @@ The configuration file for DCC-EX Command Station
// //
// #define DISABLE_EEPROM // #define DISABLE_EEPROM
/////////////////////////////////////////////////////////////////////////////////////
// DISABLE PROG
//
// If you do not need programming capability, you can disable all programming related
// commands. You might want to do that if you are using an Arduino UNO and still want
// to use EXRAIL automation, as the Uno is lacking in RAM and Flash to run both.
//
// Note this disables all programming functionality, including EXRAIL.
//
// #define DISABLE_PROG
///////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////
// REDEFINE WHERE SHORT/LONG ADDR break is. According to NMRA the last short address // REDEFINE WHERE SHORT/LONG ADDR break is. According to NMRA the last short address
// is 127 and the first long address is 128. There are manufacturers which have // is 127 and the first long address is 128. There are manufacturers which have
@ -266,15 +224,5 @@ The configuration file for DCC-EX Command Station
// //
//#define SERIAL_BT_COMMANDS //#define SERIAL_BT_COMMANDS
// SABERTOOTH
//
// This is a very special option and only useful if you happen to have a
// sabertooth motor controller from dimension engineering configured to
// take commands from and ESP32 via serial at 9600 baud from GPIO17 (TX)
// and GPIO16 (RX, currently unused).
// The number defined is the DCC address for which speed controls are sent
// to the sabertooth controller _as_well_. Default: Undefined.
//
//#define SABERTOOTH 1
///////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////

169
config.h.txt Normal file
View File

@ -0,0 +1,169 @@
/**********************************************************************
Config.h
COPYRIGHT (c) 2013-2016 Gregg E. Berman
COPYRIGHT (c) 2020 Fred Decker
The configuration file for DCC++ EX Command Station
**********************************************************************/
/////////////////////////////////////////////////////////////////////////////////////
// NOTE: Before connecting these boards and selecting one in this software
// check the quick install guides!!! Some of these boards require a voltage
// generating resitor on the current sense pin of the device. Failure to select
// the correct resistor could damage the sense pin on your Arduino or destroy
// the device.
//
// DEFINE MOTOR_SHIELD_TYPE BELOW ACCORDING TO THE FOLLOWING TABLE:
//
// STANDARD_MOTOR_SHIELD : Arduino Motor shield Rev3 based on the L298 with 18V 2A per channel
// POLOLU_MOTOR_SHIELD : Pololu MC33926 Motor Driver (not recommended for prog track)
// FUNDUMOTO_SHIELD : Fundumoto Shield, no current sensing (not recommended, no short protection)
// FIREBOX_MK1 : The Firebox MK1
// FIREBOX_MK1S : The Firebox MK1S
// |
// +-----------------------v
//
// #define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"),
// new MotorDriver(3, 12, UNUSED_PIN, 9, A0, 0.488, 1500, UNUSED_PIN),
// new MotorDriver(11, 13, UNUSED_PIN, 8, A1, 0.488, 1500, UNUSED_PIN)
#define MOTOR_SHIELD_TYPE STANDARD_MOTOR_SHIELD
/////////////////////////////////////////////////////////////////////////////////////
//
// The IP port to talk to a WIFI or Ethernet shield.
//
#define IP_PORT 2560
/////////////////////////////////////////////////////////////////////////////////////
//
// NOTE: Only supported on Arduino Mega
// Set to false if you not even want it on the Arduino Mega
//
//#define ENABLE_WIFI true
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE WiFi Parameters (only in effect if WIFI is on)
//
// If DONT_TOUCH_WIFI_CONF is set, all WIFI config will be done with
// the <+> commands and this sketch will not change anything over
// AT commands and the other WIFI_* defines below do not have any effect.
//#define DONT_TOUCH_WIFI_CONF
//
// WIFI_SSID is the network name IF you want to use your existing home network.
// Do NOT change this if you want to use the WiFi in Access Point (AP) mode.
//
// If you do NOT set the WIFI_SSID, the WiFi chip will first try
// to connect to the previously configured network and if that fails
// fall back to Access Point mode. The SSID of the AP will be
// automatically set to DCCEX_*.
//
// Your SSID may not conain ``"'' (double quote, ASCII 0x22).
#define WIFI_SSID "Your network name"
//
// WIFI_PASSWORD is the network password for your home network or if
// you want to change the password from default AP mode password
// to the AP password you want.
// Your password may not conain ``"'' (double quote, ASCII 0x22).
#define WIFI_PASSWORD "deadcafe"
//
// WIFI_HOSTNAME: You probably don't need to change this
#define WIFI_HOSTNAME "dccex"
//
/////////////////////////////////////////////////////////////////////////////////////
//
// Wifi connect timeout in milliseconds. Default is 14000 (14 seconds). You only need
// to set this if you have an extremely slow Wifi router.
//
#define WIFI_CONNECT_TIMEOUT 14000
/////////////////////////////////////////////////////////////////////////////////////
//
// ENABLE_ETHERNET: Set to true if you have an Arduino Ethernet card (wired). This
// is not for Wifi. You will then need the Arduino Ethernet library as well
//
//#define ENABLE_ETHERNET true
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE STATIC IP ADDRESS *OR* COMMENT OUT TO USE DHCP
//
//#define IP_ADDRESS { 192, 168, 1, 31 }
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE MAC ADDRESS ARRAY FOR ETHERNET COMMUNICATIONS INTERFACE
//
// Uncomment to use with Ethernet Shields
//
// Ethernet Shields do not have have a MAC address in hardware. There may be one on
// a sticker on the Shield that you should use. Otherwise choose one of the ones below
// Be certain that no other device on your network has this same MAC address!
//
// 52:b8:8a:8e:ce:21
// e3:e9:73:e1:db:0d
// 54:2b:13:52:ac:0c
// NOTE: This is not used with ESP8266 WiFi modules.
//#define MAC_ADDRESS { 0x52, 0xB8, 0x8A, 0x8E, 0xCE, 0x21 } // MAC address of your networking card found on the sticker on your card or take one from above
//
// #define MAC_ADDRESS { 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xEF }
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE LCD SCREEN USAGE BY THE BASE STATION
//
// Note: This feature requires an I2C enabled LCD screen using a Hitachi HD44780
// controller and a PCF8574 based I2C 'backpack',
// OR an I2C Oled screen based on SSD1306 (128x64 or 128x32) controller,
// OR an I2C Oled screen based on SH1106 (132x64) controller.
// To enable, uncomment one of the lines below
// define LCD_DRIVER for I2C LCD address 0x3f,16 cols, 2 rows
//#define LCD_DRIVER {SubBus_4,0x27},20,4
//OR define OLED_DRIVER width,height in pixels (address auto detected)
#if defined(ARDUINO_ARCH_STM32)
#define OLED_DRIVER 0x3c, 128, 64
#else
#define OLED_DRIVER {SubBus_0,0x3c}, 128, 32
#endif
#define SCROLLMODE 1
/////////////////////////////////////////////////////////////////////////////////////
// DISABLE EEPROM
//
// If you do not need the EEPROM at all, you can disable all the code that saves
// data in the EEPROM. You might want to do that if you are in a Arduino UNO
// and want to use the EX-RAIL automation. Otherwise you do not have enough RAM
// to do that. Of course, then none of the EEPROM related commands work.
//
#define DISABLE_EEPROM
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE TURNOUTS/ACCESSORIES FOLLOW NORM RCN-213
//
// According to norm RCN-213 a DCC packet with a 1 is closed/straight
// and one with a 0 is thrown/diverging. In DCC++ Classic, and in previous
// versions of DCC++EX, a turnout throw command was implemented in the packet as
// '1' and a close command as '0'. The #define below makes the states
// match with the norm. But we don't want to cause havoc on existent layouts,
// so we define this only for new installations. If you don't want this,
// don't add it to your config.h.
//#define DCC_TURNOUTS_RCN_213
// The following #define likewise inverts the behaviour of the <a> command
// for triggering DCC Accessory Decoders, so that <a addr subaddr 0> generates a
// DCC packet with D=1 (close turnout) and <a addr subaddr 1> generates D=0
// (throw turnout).
//#define DCC_ACCESSORY_RCN_213
/////////////////////////////////////////////////////////////////////////////////////

View File

@ -148,6 +148,7 @@
#define I2C_USE_WIRE #define I2C_USE_WIRE
#endif #endif
/* TODO when ready /* TODO when ready
#elif defined(ARDUINO_ARCH_RP2040) #elif defined(ARDUINO_ARCH_RP2040)
#define ARDUINO_TYPE "RP2040" #define ARDUINO_TYPE "RP2040"
@ -182,15 +183,6 @@
#define WIFI_ON false #define WIFI_ON false
#endif #endif
#ifndef WIFI_FORCE_AP
#define WIFI_FORCE_AP false
#else
#if WIFI_FORCE_AP==true || WIFI_FORCE_AP==false
#else
#error WIFI_FORCE_AP needs to be true or false
#endif
#endif
#if ENABLE_ETHERNET #if ENABLE_ETHERNET
#if defined(HAS_ENOUGH_MEMORY) #if defined(HAS_ENOUGH_MEMORY)
#define ETHERNET_ON true #define ETHERNET_ON true
@ -214,7 +206,7 @@
#define WIFI_SERIAL_LINK_SPEED 115200 #define WIFI_SERIAL_LINK_SPEED 115200
#if __has_include ( "myAutomation.h") #if __has_include ( "myAutomation.h")
#if defined(HAS_ENOUGH_MEMORY) || defined(DISABLE_EEPROM) || defined(DISABLE_PROG) #if defined(HAS_ENOUGH_MEMORY) || defined(DISABLE_EEPROM)
#define EXRAIL_ACTIVE #define EXRAIL_ACTIVE
#else #else
#define EXRAIL_WARNING #define EXRAIL_WARNING

View File

@ -1,7 +1,7 @@
#!/bin/bash #!/bin/bash
# #
# © 2022,2023 Harald Barth # © 2022 Harald Barth
# #
# This file is part of CommandStation-EX # This file is part of CommandStation-EX
# #
@ -29,33 +29,14 @@ ACLI="./bin/arduino-cli"
function need () { function need () {
type -p $1 > /dev/null && return type -p $1 > /dev/null && return
dpkg -l $1 2>&1 | egrep ^ii >/dev/null && return
sudo apt-get install $1 sudo apt-get install $1
type -p $1 > /dev/null && return type -p $1 > /dev/null && return
echo "Could not install $1, abort" echo "Could not install $1, abort"
exit 255 exit 255
} }
need git need git
if cat /etc/issue | egrep '^Raspbian' 2>&1 >/dev/null ; then
# we are on a raspi where we do not support graphical
unset DISPLAY
fi
if [ x$DISPLAY != x ] ; then
# we have DISPLAY, do the graphic thing
need python3-tk
need python3.8-venv
mkdir -p ~/ex-installer/venv
python3 -m venv ~/ex-installer/venv
cd ~/ex-installer/venv || exit 255
source ./bin/activate
git clone https://github.com/DCC-EX/EX-Installer
cd EX-Installer || exit 255
pip3 install -r requirements.txt
exec python3 -m ex_installer
fi
if test -d `basename "$DCCEXGITURL"` ; then if test -d `basename "$DCCEXGITURL"` ; then
: assume we are almost there : assume we are almost there
cd `basename "$DCCEXGITURL"` || exit 255 cd `basename "$DCCEXGITURL"` || exit 255

View File

@ -173,8 +173,6 @@ board = esp32dev
framework = arduino framework = arduino
lib_deps = ${env.lib_deps} lib_deps = ${env.lib_deps}
build_flags = -std=c++17 build_flags = -std=c++17
monitor_speed = 115200
monitor_echo = yes
[env:Nucleo-F411RE] [env:Nucleo-F411RE]
platform = ststm32 platform = ststm32
@ -190,7 +188,7 @@ platform = ststm32
board = nucleo_f446re board = nucleo_f446re
framework = arduino framework = arduino
lib_deps = ${env.lib_deps} lib_deps = ${env.lib_deps}
build_flags = -std=c++17 -Os -g2 -Wunused-variable ; -DDIAG_LOOPTIMES ; -DDIAG_IO build_flags = -std=c++17 -Os -g2 -Wunused-variable -DDIAG_LOOPTIMES ; -DDIAG_IO
monitor_speed = 115200 monitor_speed = 115200
monitor_echo = yes monitor_echo = yes

View File

@ -3,43 +3,8 @@
#include "StringFormatter.h" #include "StringFormatter.h"
#define VERSION "5.0.1"
// 5.0.1 - Check bad AT firmware version #define VERSION "4.2.47"
// 5.0.0 - Make 4.2.69 the 5.0.0 release
// 4.2.69 - Bugfix: Make <!> work in DC mode
// 4.2.68 - Rename track mode OFF to NONE
// 4.2.67 - AVR: Pin specific timer register seting
// - Protect Uno user from choosing DC(X)
// - More Nucleo variant defines
// - GPIO PCA9555 / TCA9555 support
// 4.2.66 - Throttle inrush current by applying PWM to brake pin when
// fault pin goes active
// 4.2.65 - new config WIFI_FORCE_AP option
// 4.2.63 - completely new overcurrent detection
// - ESP32 protect from race in RMT code
// 4.2.62 - Update IO_RotaryEncoder.h to ignore sending current position
// - Update IO_EXTurntable.h to remove forced I2C clock speed
// - Show device offline if EX-Turntable not connected
// 4.2.61 - MAX_CURRENT restriction (caps motor shield value)
// 4.2.60 - Add mDNS capability to ESP32 for autodiscovery
// 4.2.59 - Fix: AP SSID was DCC_ instead of DCCEX_
// 4.2.58 - Start motordriver as soon as possible but without waveform
// 4.2.57 - New overload handling (faster and handles commonFaultPin again)
// - Optimize analog read STM32
// 4.2.56 - Update IO_RotaryEncoder.h:
// - Improved I2C communication, non-blocking reads
// - Enable sending positions to the encoder from EXRAIL via SERVO()
// 4.2.55 - Optimize analog read for AVR
// 4.2.54 - EX8874 shield in config.example.h
// - Fix: Better warnings for pin number errors
// - Fix: Default roster list possible in Withrottle and <jR>
// - Fix: Pin handling supports pins up to 254
// 4.2.53 - Fix: Fault pin handling made more straight forward
// 4.2.52 - Experimental support for sabertooth motor controller on ESP32
// 4.2.51 - Add DISABLE_PROG to disable programming to save RAM/Flash
// 4.2.50 - Fixes: estop all, turnout eeprom, cab ID check
// 4.2.49 - Exrail SPEED take notice of external direction change
// 4.2.48 - BROADCAST/WITHROTTLE Exrail macros
// 4.2.47 - Correct response to <JA 0> // 4.2.47 - Correct response to <JA 0>
// 4.2.46 - Support boards with inverted fault pin // 4.2.46 - Support boards with inverted fault pin
// 4.2.45 - Add ONCLOCKMINS to FastClock to allow hourly repeat events // 4.2.45 - Add ONCLOCKMINS to FastClock to allow hourly repeat events