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

Merge branch 'devel' into devel-pauls-i2c-devices

This commit is contained in:
Asbelos 2024-09-03 10:07:12 +01:00
commit c6f2db7909
47 changed files with 1459 additions and 268 deletions

View File

@ -37,7 +37,7 @@ int16_t lastclocktime;
int8_t lastclockrate;
#if WIFI_ON || ETHERNET_ON || defined(SERIAL1_COMMANDS) || defined(SERIAL2_COMMANDS) || defined(SERIAL3_COMMANDS)
#if WIFI_ON || ETHERNET_ON || defined(SERIAL1_COMMANDS) || defined(SERIAL2_COMMANDS) || defined(SERIAL3_COMMANDS) || defined(SERIAL4_COMMANDS) || defined(SERIAL5_COMMANDS) || defined(SERIAL6_COMMANDS)
// use a buffer to allow broadcast
StringBuffer * CommandDistributor::broadcastBufferWriter=new StringBuffer();
template<typename... Targs> void CommandDistributor::broadcastReply(clientType type, Targs... msg){
@ -209,9 +209,7 @@ int16_t CommandDistributor::retClockTime() {
void CommandDistributor::broadcastLoco(byte slot) {
DCC::LOCO * sp=&DCC::speedTable[slot];
uint32_t func = sp->functions;
func = func & 0x1fffffff; // mask out bits 0-28
broadcastReply(COMMAND_TYPE, F("<l %d %d %d %l>\n"), sp->loco,slot,sp->speedCode,func);
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;
@ -250,6 +248,10 @@ void CommandDistributor::broadcastLoco(byte slot) {
#endif
}
void CommandDistributor::broadcastForgetLoco(int16_t loco) {
broadcastReply(COMMAND_TYPE, F("<l %d 0 1 0>\n<- %d>\n"), loco,loco);
}
void CommandDistributor::broadcastPower() {
char pstr[] = "? x";
for(byte t=0; t<TrackManager::MAX_TRACKS; t++)
@ -312,6 +314,11 @@ void CommandDistributor::broadcastRaw(clientType type, char * msg) {
broadcastReply(type, F("%s"),msg);
}
void CommandDistributor::broadcastMessage(char * message) {
broadcastReply(COMMAND_TYPE, F("<m \"%s\">\n"),message);
broadcastReply(WITHROTTLE_TYPE, F("Hm%s\n"),message);
}
void CommandDistributor::broadcastTrackState(const FSH* format, byte trackLetter, const FSH *modename, int16_t dcAddr) {
broadcastReply(COMMAND_TYPE, format, trackLetter, modename, dcAddr);
}

View File

@ -47,6 +47,7 @@ private:
public :
static void parse(byte clientId,byte* buffer, RingStream * ring);
static void broadcastLoco(byte slot);
static void broadcastForgetLoco(int16_t loco);
static void broadcastSensor(int16_t id, bool value);
static void broadcastTurnout(int16_t id, bool isClosed);
static void broadcastTurntable(int16_t id, uint8_t position, bool moving);
@ -60,6 +61,7 @@ public :
static void forget(byte clientId);
static void broadcastRouteState(uint16_t routeId,byte state);
static void broadcastRouteCaption(uint16_t routeId,const FSH * caption);
static void broadcastMessage(char * message);
// Handling code for virtual LCD receiver.
static Print * getVirtualLCDSerial(byte screen, byte row);

View File

@ -65,6 +65,9 @@
#ifdef EXRAIL_WARNING
#warning You have myAutomation.h but your hardware has not enough memory to do that, so EX-RAIL DISABLED
#endif
// compile time check, passwords 1 to 7 chars do not work, so do not try to compile with them at all
// remember trailing '\0', sizeof("") == 1.
#define PASSWDCHECK(S) static_assert(sizeof(S) == 1 || sizeof(S) > 8, "Password shorter than 8 chars")
void setup()
{
@ -102,10 +105,12 @@ void setup()
// Start Ethernet if it exists
#ifndef ARDUINO_ARCH_ESP32
#if WIFI_ON
PASSWDCHECK(WIFI_PASSWORD); // compile time check
WifiInterface::setup(WIFI_SERIAL_LINK_SPEED, F(WIFI_SSID), F(WIFI_PASSWORD), F(WIFI_HOSTNAME), IP_PORT, WIFI_CHANNEL, WIFI_FORCE_AP);
#endif // WIFI_ON
#else
// ESP32 needs wifi on always
PASSWDCHECK(WIFI_PASSWORD); // compile time check
WifiESP::setup(WIFI_SSID, WIFI_PASSWORD, WIFI_HOSTNAME, IP_PORT, WIFI_CHANNEL, WIFI_FORCE_AP);
#endif // ARDUINO_ARCH_ESP32

105
DCC.cpp
View File

@ -219,8 +219,9 @@ bool DCC::setFn( int cab, int16_t functionNumber, bool on) {
} else {
speedTable[reg].functions &= ~funcmask;
}
if (speedTable[reg].functions != previous && functionNumber <= 28) {
updateGroupflags(speedTable[reg].groupFlags, functionNumber);
if (speedTable[reg].functions != previous) {
if (functionNumber <= 28)
updateGroupflags(speedTable[reg].groupFlags, functionNumber);
CommandDistributor::broadcastLoco(reg);
}
return true;
@ -235,14 +236,14 @@ void DCC::changeFn( int cab, int16_t functionNumber) {
speedTable[reg].functions ^= funcmask;
if (functionNumber <= 28) {
updateGroupflags(speedTable[reg].groupFlags, functionNumber);
CommandDistributor::broadcastLoco(reg);
}
CommandDistributor::broadcastLoco(reg);
}
// Report function state (used from withrottle protocol)
// returns 0 false, 1 true or -1 for do not know
int8_t DCC::getFn( int cab, int16_t functionNumber) {
if (cab<=0 || functionNumber>28)
if (cab<=0 || functionNumber>31)
return -1; // unknown
int reg = lookupSpeedTable(cab);
if (reg<0)
@ -270,6 +271,20 @@ uint32_t DCC::getFunctionMap(int cab) {
return (reg<0)?0:speedTable[reg].functions;
}
// saves DC frequency (0..3) in spare functions 29,30,31
void DCC::setDCFreq(int cab,byte freq) {
if (cab==0 || freq>3) return;
auto reg=lookupSpeedTable(cab,true);
// drop and replace F29,30,31 (top 3 bits)
auto newFunctions=speedTable[reg].functions & 0x1FFFFFFFUL;
if (freq==1) newFunctions |= (1UL<<29); // F29
else if (freq==2) newFunctions |= (1UL<<30); // F30
else if (freq==3) newFunctions |= (1UL<<31); // F31
if (newFunctions==speedTable[reg].functions) return; // no change
speedTable[reg].functions=newFunctions;
CommandDistributor::broadcastLoco(reg);
}
void DCC::setAccessory(int address, byte port, bool gate, byte onoff /*= 2*/) {
// onoff is tristate:
// 0 => send off packet
@ -324,8 +339,8 @@ preamble -0- 1 0 A7 A6 A5 A4 A3 A2 -0- 0 ^A10 ^A9 ^A8 0 A1 A0 1 -0- ....
Thus in byte packet form the format is 10AAAAAA, 0AAA0AA1, 000XXXXX
Die Adresse für den ersten erweiterten Zubehördecoder ist wie bei den einfachen
Zubehördecodern die Adresse 4 = 1000-0001 0111-0001 . Diese Adresse wird in
Die Adresse f<EFBFBD>r den ersten erweiterten Zubeh<EFBFBD>rdecoder ist wie bei den einfachen
Zubeh<EFBFBD>rdecodern die Adresse 4 = 1000-0001 0111-0001 . Diese Adresse wird in
Anwenderdialogen als Adresse 1 dargestellt.
This means that the first address shown to the user as "1" is mapped
@ -499,6 +514,36 @@ const ackOp FLASH READ_CV_PROG[] = {
const ackOp FLASH LOCO_ID_PROG[] = {
BASELINE,
// first check cv20 for extended addressing
SETCV, (ackOp)20, // CV 19 is extended
SETBYTE, (ackOp)0,
VB, WACK, ITSKIP, // skip past extended section if cv20 is zero
// read cv20 and 19 and merge
STARTMERGE, // Setup to read cv 20
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
VB, WACK, NAKSKIP, // bad read of cv20, assume its 0
STASHLOCOID, // keep cv 20 until we have cv19 as well.
SETCV, (ackOp)19,
STARTMERGE, // Setup to read cv 19
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
VB, WACK, NAKFAIL, // cant recover if cv 19 unreadable
COMBINE1920, // Combile byte with stash and callback
// end of advanced 20,19 check
SKIPTARGET,
SETCV, (ackOp)19, // CV 19 is consist setting
SETBYTE, (ackOp)0,
VB, WACK, ITSKIP, // ignore consist if cv19 is zero (no consist)
@ -565,6 +610,10 @@ const ackOp FLASH LOCO_ID_PROG[] = {
const ackOp FLASH SHORT_LOCO_ID_PROG[] = {
BASELINE,
// Clear consist CV 19,20
SETCV,(ackOp)20,
SETBYTE, (ackOp)0,
WB,WACK, // ignore dedcoder without cv20 support
SETCV,(ackOp)19,
SETBYTE, (ackOp)0,
WB,WACK, // ignore dedcoder without cv19 support
@ -580,9 +629,25 @@ const ackOp FLASH SHORT_LOCO_ID_PROG[] = {
CALLFAIL
};
// for CONSIST_ID_PROG the 20,19 values are already calculated
const ackOp FLASH CONSIST_ID_PROG[] = {
BASELINE,
SETCV,(ackOp)20,
SETBYTEH, // high byte to CV 20
WB,WACK, // ignore dedcoder without cv20 support
SETCV,(ackOp)19,
SETBYTEL, // low byte of word
WB,WACK,ITC1, // If ACK, we are done - callback(1) means Ok
VB,WACK,ITC1, // Some decoders do not ack and need verify
CALLFAIL
};
const ackOp FLASH LONG_LOCO_ID_PROG[] = {
BASELINE,
// Clear consist CV 19
// Clear consist CV 19,20
SETCV,(ackOp)20,
SETBYTE, (ackOp)0,
WB,WACK, // ignore dedcoder without cv20 support
SETCV,(ackOp)19,
SETBYTE, (ackOp)0,
WB,WACK, // ignore decoder without cv19 support
@ -651,17 +716,41 @@ void DCC::setLocoId(int id,ACK_CALLBACK callback) {
DCCACK::Setup(id | 0xc000,LONG_LOCO_ID_PROG, callback);
}
void DCC::setConsistId(int id,bool reverse,ACK_CALLBACK callback) {
if (id<0 || id>10239) { //0x27FF according to standard
callback(-1);
return;
}
byte cv20;
byte cv19;
if (id<=HIGHEST_SHORT_ADDR) {
cv19=id;
cv20=0;
}
else {
cv20=id/100;
cv19=id%100;
}
if (reverse) cv19|=0x80;
DCCACK::Setup((cv20<<8)|cv19, CONSIST_ID_PROG, callback);
}
void DCC::forgetLoco(int cab) { // removes any speed reminders for this loco
setThrottle2(cab,1); // ESTOP this loco if still on track
int reg=lookupSpeedTable(cab, false);
if (reg>=0) {
speedTable[reg].loco=0;
setThrottle2(cab,1); // ESTOP if this loco still on track
CommandDistributor::broadcastForgetLoco(cab);
}
}
void DCC::forgetAllLocos() { // removes all speed reminders
setThrottle2(0,1); // ESTOP all locos still on track
for (int i=0;i<MAX_LOCOS;i++) speedTable[i].loco=0;
for (int i=0;i<MAX_LOCOS;i++) {
if (speedTable[i].loco) CommandDistributor::broadcastForgetLoco(speedTable[i].loco);
speedTable[i].loco=0;
}
}
byte DCC::loopStatus=0;

3
DCC.h
View File

@ -70,6 +70,7 @@ public:
static void changeFn(int cab, int16_t functionNumber);
static int8_t getFn(int cab, int16_t functionNumber);
static uint32_t getFunctionMap(int cab);
static void setDCFreq(int cab,byte freq);
static void updateGroupflags(byte &flags, int16_t functionNumber);
static void setAccessory(int address, byte port, bool gate, byte onoff = 2);
static bool setExtendedAccessory(int16_t address, int16_t value, byte repeats=3);
@ -85,7 +86,7 @@ public:
static void getLocoId(ACK_CALLBACK callback);
static void setLocoId(int id,ACK_CALLBACK callback);
static void setConsistId(int id,bool reverse,ACK_CALLBACK callback);
// Enhanced API functions
static void forgetLoco(int cab); // removes any speed reminders for this loco
static void forgetAllLocos(); // removes all speed reminders

View File

@ -27,8 +27,8 @@
#include "DCCWaveform.h"
#include "TrackManager.h"
unsigned int DCCACK::minAckPulseDuration = 2000; // micros
unsigned int DCCACK::maxAckPulseDuration = 20000; // micros
unsigned long DCCACK::minAckPulseDuration = 2000; // micros
unsigned long DCCACK::maxAckPulseDuration = 20000; // micros
MotorDriver * DCCACK::progDriver=NULL;
ackOp const * DCCACK::ackManagerProg;
@ -50,8 +50,8 @@ volatile uint8_t DCCACK::numAckSamples=0;
uint8_t DCCACK::trailingEdgeCounter=0;
unsigned int DCCACK::ackPulseDuration; // micros
unsigned long DCCACK::ackPulseStart; // micros
unsigned long DCCACK::ackPulseDuration; // micros
unsigned long DCCACK::ackPulseStart; // micros
volatile bool DCCACK::ackDetected;
unsigned long DCCACK::ackCheckStart; // millis
volatile bool DCCACK::ackPending;
@ -127,7 +127,7 @@ bool DCCACK::checkResets(uint8_t numResets) {
void DCCACK::setAckBaseline() {
int baseline=progDriver->getCurrentRaw();
ackThreshold= baseline + progDriver->mA2raw(ackLimitmA);
if (Diag::ACK) DIAG(F("ACK baseline=%d/%dmA Threshold=%d/%dmA Duration between %uus and %uus"),
if (Diag::ACK) DIAG(F("ACK baseline=%d/%dmA Threshold=%d/%dmA Duration between %lus and %lus"),
baseline,progDriver->raw2mA(baseline),
ackThreshold,progDriver->raw2mA(ackThreshold),
minAckPulseDuration, maxAckPulseDuration);
@ -146,7 +146,7 @@ void DCCACK::setAckPending() {
byte DCCACK::getAck() {
if (ackPending) return (2); // still waiting
if (Diag::ACK) DIAG(F("%S after %dmS max=%d/%dmA pulse=%uuS samples=%d gaps=%d"),ackDetected?F("ACK"):F("NO-ACK"), ackCheckDuration,
if (Diag::ACK) DIAG(F("%S after %dmS max=%d/%dmA pulse=%luS samples=%d gaps=%d"),ackDetected?F("ACK"):F("NO-ACK"), ackCheckDuration,
ackMaxCurrent,progDriver->raw2mA(ackMaxCurrent), ackPulseDuration, numAckSamples, numAckGaps);
if (ackDetected) return (1); // Yes we had an ack
return(0); // pending set off but not detected means no ACK.
@ -314,6 +314,14 @@ void DCCACK::loop() {
callback( LONG_ADDR_MARKER | ( ackManagerByte + ((ackManagerStash - 192) << 8)));
return;
case COMBINE1920:
// ackManagerStash is cv20, ackManagerByte is CV 19
// This will not be called if cv20==0
ackManagerByte &= 0x7F; // ignore direction marker
ackManagerByte %=100; // take last 2 decimal digits
callback( ackManagerStash*100+ackManagerByte);
return;
case ITSKIP:
if (!ackReceived) break;
// SKIP opcodes until SKIPTARGET found
@ -322,6 +330,15 @@ void DCCACK::loop() {
opcode=GETFLASH(ackManagerProg);
}
break;
case NAKSKIP:
if (ackReceived) break;
// SKIP opcodes until SKIPTARGET found
while (opcode!=SKIPTARGET) {
ackManagerProg++;
opcode=GETFLASH(ackManagerProg);
}
break;
case SKIPTARGET:
break;
default:

View File

@ -56,6 +56,8 @@ enum ackOp : byte
STASHLOCOID, // keeps current byte value for later
COMBINELOCOID, // combines current value with stashed value and returns it
ITSKIP, // skip to SKIPTARGET if ack true
NAKSKIP, // skip to SKIPTARGET if ack false
COMBINE1920, // combine cvs 19 and 20 and callback
SKIPTARGET = 0xFF // jump to target
};
@ -77,10 +79,10 @@ class DCCACK {
static inline void setAckLimit(int mA) {
ackLimitmA = mA;
}
static inline void setMinAckPulseDuration(unsigned int i) {
static inline void setMinAckPulseDuration(unsigned long i) {
minAckPulseDuration = i;
}
static inline void setMaxAckPulseDuration(unsigned int i) {
static inline void setMaxAckPulseDuration(unsigned long i) {
maxAckPulseDuration = i;
}
@ -124,11 +126,11 @@ class DCCACK {
static unsigned long ackCheckStart; // millis
static unsigned int ackCheckDuration; // millis
static unsigned int ackPulseDuration; // micros
static unsigned long ackPulseDuration; // micros
static unsigned long ackPulseStart; // micros
static unsigned int minAckPulseDuration ; // micros
static unsigned int maxAckPulseDuration ; // micros
static unsigned long minAckPulseDuration ; // micros
static unsigned long maxAckPulseDuration ; // micros
static MotorDriver* progDriver;
static volatile uint8_t numAckGaps;
static volatile uint8_t numAckSamples;

View File

@ -2,7 +2,7 @@
* © 2022 Paul M Antoine
* © 2021 Neil McKechnie
* © 2021 Mike S
* © 2021 Herb Morton
* © 2021-2024 Herb Morton
* © 2020-2023 Harald Barth
* © 2020-2021 M Steve Todd
* © 2020-2021 Fred Decker
@ -68,10 +68,10 @@ Once a new OPCODE is decided upon, update this list.
K, Reserved for future use - Potentially Railcom
l, Loco speedbyte/function map broadcast
L, Reserved for LCC interface (implemented in EXRAIL)
m,
m, message to throttles broadcast
M, Write DCC packet
n,
N,
n, Reserved for SensorCam
N, Reserved for Sensorcam
o,
O, Output broadcast
p, Broadcast power state
@ -91,10 +91,10 @@ Once a new OPCODE is decided upon, update this list.
w, Write CV on main
W, Write CV
x,
X, Invalid command
y,
X, Invalid command response
y,
Y, Output broadcast
z,
z, Direct output
Z, Output configuration/control
*/
@ -283,25 +283,22 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
return; // filterCallback asked us to ignore
case 't': // THROTTLE <t [REGISTER] CAB SPEED DIRECTION>
{
if (params==1) { // <t cab> display state
int16_t slot=DCC::lookupSpeedTable(p[0],false);
if (slot>=0) {
DCC::LOCO * sp=&DCC::speedTable[slot];
StringFormatter::send(stream,F("<l %d %d %d %l>\n"),
sp->loco,slot,sp->speedCode,sp->functions);
}
else // send dummy state speed 0 fwd no functions.
StringFormatter::send(stream,F("<l %d -1 128 0>\n"),p[0]);
return;
}
int16_t cab;
int16_t tspeed;
int16_t direction;
if (params==1) { // <t cab> display state
int16_t slot=DCC::lookupSpeedTable(p[0],false);
if (slot>=0)
CommandDistributor::broadcastLoco(slot);
else // send dummy state speed 0 fwd no functions.
StringFormatter::send(stream,F("<l %d -1 128 0>\n"),p[0]);
return;
}
if (params == 4)
{ // <t REGISTER CAB SPEED DIRECTION>
// ignore register p[0]
cab = p[1];
tspeed = p[2];
direction = p[3];
@ -461,6 +458,9 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
DCC::setLocoId(p[0],callback_Wloco);
else if (params == 4) // WRITE CV ON PROG <W CV VALUE [CALLBACKNUM] [CALLBACKSUB]>
DCC::writeCVByte(p[0], p[1], callback_W4);
else if ((params==2 || params==3 ) && p[0]=="CONSIST"_hk ) {
DCC::setConsistId(p[1],p[2]=="REVERSE"_hk,callback_Wconsist);
}
else if (params == 2) // WRITE CV ON PROG <W CV VALUE>
DCC::writeCVByte(p[0], p[1], callback_W);
else
@ -563,6 +563,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
}
#ifndef DISABLE_PROG
else if (p[0]=="PROG"_hk) { // <0 PROG>
TrackManager::setJoin(false);
TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off
TrackManager::setTrackPower(TRACK_MODE_PROG, POWERMODE::OFF);
}
@ -641,6 +642,13 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
case 'F': // New command to call the new Loco Function API <F cab func 1|0>
if(params!=3) break;
if (p[1]=="DCFREQ"_hk) { // <F cab DCFREQ 0..3>
if (p[2]<0 || p[2]>3) break;
DCC::setDCFreq(p[0],p[2]);
return;
}
if (Diag::CMD)
DIAG(F("Setting loco %d F%d %S"), p[0], p[1], p[2] ? F("ON") : F("OFF"));
if (DCC::setFn(p[0], p[1], p[2] == 1)) return;
@ -800,6 +808,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
break;
#endif
case '/': // implemented in EXRAIL parser
case 'L': // LCC interface implemented in EXRAIL parser
break; // Will <X> if not intercepted by EXRAIL
@ -1072,15 +1081,24 @@ bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) {
#ifndef DISABLE_PROG
case "ACK"_hk: // <D ACK ON/OFF> <D ACK [LIMIT|MIN|MAX|RETRY] Value>
if (params >= 3) {
long duration;
if (p[1] == "LIMIT"_hk) {
DCCACK::setAckLimit(p[2]);
LCD(1, F("Ack Limit=%dmA"), p[2]); // <D ACK LIMIT 42>
LCD(1, F("Ack Limit=%dmA"), p[2]); // <D ACK LIMIT 42>
} else if (p[1] == "MIN"_hk) {
DCCACK::setMinAckPulseDuration(p[2]);
LCD(0, F("Ack Min=%uus"), p[2]); // <D ACK MIN 1500>
if (params == 4 && p[3] == "MS"_hk)
duration = p[2] * 1000L;
else
duration = p[2];
DCCACK::setMinAckPulseDuration(duration);
LCD(0, F("Ack Min=%lus"), duration); // <D ACK MIN 1500>
} else if (p[1] == "MAX"_hk) {
DCCACK::setMaxAckPulseDuration(p[2]);
LCD(0, F("Ack Max=%uus"), p[2]); // <D ACK MAX 9000>
if (params == 4 && p[3] == "MS"_hk) // <D ACK MAX 80 MS>
duration = p[2] * 1000L;
else
duration = p[2];
DCCACK::setMaxAckPulseDuration(duration);
LCD(0, F("Ack Max=%lus"), duration); // <D ACK MAX 9000>
} else if (p[1] == "RETRY"_hk) {
if (p[2] >255) p[2]=3;
LCD(0, F("Ack Retry=%d Sum=%d"), p[2], DCCACK::setAckRetry(p[2])); // <D ACK RETRY 2>
@ -1350,3 +1368,11 @@ void DCCEXParser::callback_Wloco(int16_t result)
StringFormatter::send(getAsyncReplyStream(), F("<w %d>\n"), result);
commitAsyncReplyStream();
}
void DCCEXParser::callback_Wconsist(int16_t result)
{
if (result==1) result=stashP[1]; // pick up original requested id from command
StringFormatter::send(getAsyncReplyStream(), F("<w CONSIST %d%S>\n"),
result, stashP[2]=="REVERSE"_hk ? F(" REVERSE") : F(""));
commitAsyncReplyStream();
}

View File

@ -71,6 +71,7 @@ struct DCCEXParser
static void callback_R(int16_t result);
static void callback_Rloco(int16_t result);
static void callback_Wloco(int16_t result);
static void callback_Wconsist(int16_t result);
static void callback_Vbit(int16_t result);
static void callback_Vbyte(int16_t result);
static FILTER_CALLBACK filterCallback;

View File

@ -1,5 +1,5 @@
/*
* © 2022-2023 Paul M. Antoine
* © 2022-2024 Paul M. Antoine
* © 2021 Mike S
* © 2021-2023 Harald Barth
* © 2021 Fred Decker
@ -65,7 +65,11 @@ class DCCTimer {
static void startRailcomTimer(byte brakePin);
static void ackRailcomTimer();
static void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency);
static void DCCEXanalogWrite(uint8_t pin, int value);
static void DCCEXanalogWrite(uint8_t pin, int value, bool invert);
static void DCCEXledcDetachPin(uint8_t pin);
static void DCCEXanalogCopyChannel(int8_t frompin, int8_t topin);
static void DCCEXInrushControlOn(uint8_t pin, int duty, bool invert);
static void DCCEXledcAttachPin(uint8_t pin, int8_t channel, bool inverted);
// Update low ram level. Allow for extra bytes to be specified
// by estimation or inspection, that may be used by other
@ -131,6 +135,8 @@ private:
#if defined (ARDUINO_ARCH_STM32)
// bit array of used pins (max 32)
static uint32_t usedpins;
static uint32_t * analogchans; // Array of channel numbers to be scanned
static ADC_TypeDef * * adcchans; // Array to capture which ADC is each input channel on
#else
// bit array of used pins (max 16)
static uint16_t usedpins;

View File

@ -185,8 +185,10 @@ int DCCTimer::freeMemory() {
}
void DCCTimer::reset() {
wdt_enable( WDTO_15MS); // set Arduino watchdog timer for 15ms
delay(50); // wait for the prescaller time to expire
// 250ms chosen to circumwent bootloader bug which
// hangs at too short timepout (like 15ms)
wdt_enable( WDTO_250MS); // set Arduino watchdog timer for 250ms
delay(500); // wait for it to happen
}

View File

@ -76,8 +76,14 @@ int DCCTimer::freeMemory() {
#endif
////////////////////////////////////////////////////////////////////////
#ifdef ARDUINO_ARCH_ESP32
#include "esp_idf_version.h"
#if ESP_IDF_VERSION_MAJOR > 4
#error "DCC-EX does not support compiling with IDF version 5.0 or later. Downgrade your ESP32 library to a version that contains IDE version 4. Arduino ESP32 library 3.0.0 is too new. Downgrade to one of 2.0.9 to 2.0.17"
#endif
#include "DIAG.h"
#include <driver/adc.h>
#include <soc/sens_reg.h>
#include <soc/sens_struct.h>
@ -154,8 +160,10 @@ void DCCTimer::reset() {
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
if (f >= 16)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f);
else if (f == 7)
/*
else if (f == 7) // not used on ESP32
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 62500);
*/
else if (f >= 4)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 32000);
else if (f >= 3)
@ -188,27 +196,113 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency
}
}
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
void DCCTimer::DCCEXledcDetachPin(uint8_t pin) {
DIAG(F("Clear pin %d channel"), pin);
pin_to_channel[pin] = 0;
pinMatrixOutDetach(pin, false, false);
}
static byte LEDCToMux[] = {
LEDC_HS_SIG_OUT0_IDX,
LEDC_HS_SIG_OUT1_IDX,
LEDC_HS_SIG_OUT2_IDX,
LEDC_HS_SIG_OUT3_IDX,
LEDC_HS_SIG_OUT4_IDX,
LEDC_HS_SIG_OUT5_IDX,
LEDC_HS_SIG_OUT6_IDX,
LEDC_HS_SIG_OUT7_IDX,
LEDC_LS_SIG_OUT0_IDX,
LEDC_LS_SIG_OUT1_IDX,
LEDC_LS_SIG_OUT2_IDX,
LEDC_LS_SIG_OUT3_IDX,
LEDC_LS_SIG_OUT4_IDX,
LEDC_LS_SIG_OUT5_IDX,
LEDC_LS_SIG_OUT6_IDX,
LEDC_LS_SIG_OUT7_IDX,
};
void DCCTimer::DCCEXledcAttachPin(uint8_t pin, int8_t channel, bool inverted) {
DIAG(F("Attaching pin %d to channel %d %c"), pin, channel, inverted ? 'I' : ' ');
ledcAttachPin(pin, channel);
if (inverted) // we attach again but with inversion
gpio_matrix_out(pin, LEDCToMux[channel], inverted, 0);
}
void DCCTimer::DCCEXanalogCopyChannel(int8_t frompin, int8_t topin) {
// arguments are signed depending on inversion of pins
DIAG(F("Pin %d copied to %d"), frompin, topin);
bool inverted = false;
if (frompin<0)
frompin = -frompin;
if (topin<0) {
inverted = true;
topin = -topin;
}
int channel = pin_to_channel[frompin]; // after abs(frompin)
pin_to_channel[topin] = channel;
DCCTimer::DCCEXledcAttachPin(topin, channel, inverted);
}
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value, bool invert) {
// This allocates channels 15, 13, 11, ....
// so each channel gets its own timer.
if (pin < SOC_GPIO_PIN_COUNT) {
if (pin_to_channel[pin] == 0) {
int search_channel;
int n;
if (!cnt_channel) {
log_e("No more PWM channels available! All %u already used", LEDC_CHANNELS);
return;
}
pin_to_channel[pin] = --cnt_channel;
ledcSetup(cnt_channel, 1000, 8);
ledcAttachPin(pin, cnt_channel);
// search for free channels top down
for (search_channel=LEDC_CHANNELS-1; search_channel >=cnt_channel; search_channel -= 2) {
bool chanused = false;
for (n=0; n < SOC_GPIO_PIN_COUNT; n++) {
if (pin_to_channel[n] == search_channel) { // current search_channel used
chanused = true;
break;
}
}
if (chanused)
continue;
if (n == SOC_GPIO_PIN_COUNT) // current search_channel unused
break;
}
if (search_channel >= cnt_channel) {
pin_to_channel[pin] = search_channel;
DIAG(F("Pin %d assigned to search channel %d"), pin, search_channel);
} else {
pin_to_channel[pin] = --cnt_channel; // This sets 15, 13, ...
DIAG(F("Pin %d assigned to new channel %d"), pin, cnt_channel);
--cnt_channel; // Now we are at 14, 12, ...
}
ledcSetup(pin_to_channel[pin], 1000, 8);
DCCEXledcAttachPin(pin, pin_to_channel[pin], invert);
} else {
ledcAttachPin(pin, pin_to_channel[pin]);
// This else is only here so we can enable diag
// Pin should be already attached to channel
// DIAG(F("Pin %d assigned to old channel %d"), pin, pin_to_channel[pin]);
}
ledcWrite(pin_to_channel[pin], value);
}
}
void DCCTimer::DCCEXInrushControlOn(uint8_t pin, int duty, bool inverted) {
// this uses hardcoded channel 0
ledcSetup(0, 62500, 8);
DCCEXledcAttachPin(pin, 0, inverted);
ledcWrite(0, duty);
}
int ADCee::init(uint8_t pin) {
pinMode(pin, ANALOG);
adc1_config_width(ADC_WIDTH_BIT_12);
// Espressif deprecated ADC_ATTEN_DB_11 somewhere between 2.0.9 and 2.0.17
#ifdef ADC_ATTEN_11db
adc1_config_channel_atten(pinToADC1Channel(pin),ADC_ATTEN_11db);
#else
adc1_config_channel_atten(pinToADC1Channel(pin),ADC_ATTEN_DB_11);
#endif
return adc1_get_raw(pinToADC1Channel(pin));
}
int16_t ADCee::ADCmax() {

View File

@ -1,6 +1,6 @@
/*
* © 2023 Neil McKechnie
* © 2022-2023 Paul M. Antoine
* © 2022-2024 Paul M. Antoine
* © 2021 Mike S
* © 2021, 2023 Harald Barth
* © 2021 Fred Decker
@ -34,8 +34,22 @@
#include "TrackManager.h"
#endif
#include "DIAG.h"
#include <wiring_private.h>
#if defined(ARDUINO_NUCLEO_F401RE) || defined(ARDUINO_NUCLEO_F411RE)
#if defined(ARDUINO_NUCLEO_F401RE)
// Nucleo-64 boards don't have additional serial ports defined by default
// Serial1 is available on the F401RE, but not hugely convenient.
// Rx pin on PB7 is useful, but all the Tx pins map to Arduino digital pins, specifically:
// PA9 == D8
// PB6 == D10
// of which D8 is needed by the standard and EX8874 motor shields. D10 would be used if a second
// EX8874 is stacked. So only disable this if using a second motor shield.
HardwareSerial Serial1(PB7, PB6); // Rx=PB7, Tx=PB6 -- CN7 pin 17 and CN10 pin 17
// 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.
// Let's define Serial6 as an additional serial port (the only other option for the F401RE)
HardwareSerial Serial6(PA12, PA11); // Rx=PA12, Tx=PA11 -- CN10 pins 12 and 14 - F401RE
#elif defined(ARDUINO_NUCLEO_F411RE)
// Nucleo-64 boards don't have additional serial ports defined by default
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
@ -53,7 +67,7 @@ HardwareSerial Serial3(PC11, PC10); // Rx=PC11, Tx=PC10 -- USART3 - F446RE
HardwareSerial Serial5(PD2, PC12); // Rx=PD2, Tx=PC12 -- 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_F412ZG) || defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F446ZE) || \
defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F439ZI)
defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F439ZI) || defined(ARDUINO_NUCLEO_F4X9ZI)
// Nucleo-144 boards don't have Serial1 defined by default
HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6
HardwareSerial Serial5(PD2, PC12); // Rx=PD2, Tx=PC12 -- UART5
@ -333,7 +347,9 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency
return;
}
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value, bool invert) {
if (invert)
value = 255-value;
// Calculate percentage duty cycle from value given
uint32_t duty_cycle = (value * 100 / 256) + 1;
if (pin_timer[pin] != NULL) {
@ -361,9 +377,9 @@ void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
uint32_t ADCee::usedpins = 0; // Max of 32 ADC input channels!
uint8_t ADCee::highestPin = 0; // Highest pin to scan
int * ADCee::analogvals = NULL; // Array of analog values last captured
uint32_t * analogchans = NULL; // Array of channel numbers to be scanned
uint32_t * ADCee::analogchans = NULL; // Array of channel numbers to be scanned
// bool adc1configured = false;
ADC_TypeDef * * adcchans = NULL; // Array to capture which ADC is each input channel on
ADC_TypeDef * * ADCee::adcchans = NULL; // Array to capture which ADC is each input channel on
int16_t ADCee::ADCmax()
{
@ -381,9 +397,10 @@ int ADCee::init(uint8_t pin) {
uint32_t adcchan = STM_PIN_CHANNEL(pinmap_function(stmpin, PinMap_ADC)); // find ADC input channel
ADC_TypeDef *adc = (ADC_TypeDef *)pinmap_find_peripheral(stmpin, PinMap_ADC); // find which ADC this pin is on ADC1/2/3 etc.
int adcnum = 1;
// All variants have ADC1
if (adc == ADC1)
DIAG(F("ADCee::init(): found pin %d on ADC1"), pin);
// Checking for ADC2 and ADC3 being defined helps cater for more variants later
// Checking for ADC2 and ADC3 being defined helps cater for more variants
#if defined(ADC2)
else if (adc == ADC2)
{
@ -430,6 +447,18 @@ int ADCee::init(uint8_t pin) {
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOFEN; //Power up PORTF
gpioBase = GPIOF;
break;
#endif
#if defined(GPIOG)
case 0x06:
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOGEN; //Power up PORTG
gpioBase = GPIOG;
break;
#endif
#if defined(GPIOH)
case 0x07:
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOHEN; //Power up PORTH
gpioBase = GPIOH;
break;
#endif
default:
return -1023; // some silly value as error

View File

@ -294,7 +294,7 @@ void DCCWaveform::schedulePacket(const byte buffer[], byte byteCount, byte repea
// The resets will be zero not only now but as well repeats packets into the future
clearResets(repeats+1);
{
int ret;
int ret = 0;
do {
if(isMainTrack) {
if (rmtMainChannel != NULL)

View File

@ -1,4 +1,5 @@
/*
* © 2024 Paul M. Antoine
* © 2021 Neil McKechnie
* © 2021-2023 Harald Barth
* © 2020-2023 Chris Harlow
@ -54,6 +55,7 @@
#include "TrackManager.h"
#include "Turntables.h"
#include "IODevice.h"
#include "EXRAILSensor.h"
// One instance of RMFT clas is used for each "thread" in the automation.
@ -176,7 +178,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
/* static */ void RMFT2::begin() {
DIAG(F("EXRAIL RoutCode at =%P"),RouteCode);
//DIAG(F("EXRAIL RoutCode at =%P"),RouteCode);
bool saved_diag=diag;
diag=true;
@ -204,15 +206,16 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
// Second pass startup, define any turnouts or servos, set signals red
// add sequences onRoutines to the lookups
if (compileFeatures & FEATURE_SIGNAL) {
onRedLookup=LookListLoader(OPCODE_ONRED);
onAmberLookup=LookListLoader(OPCODE_ONAMBER);
onGreenLookup=LookListLoader(OPCODE_ONGREEN);
for (int sigslot=0;;sigslot++) {
VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8);
if (sigid==0) break; // end of signal list
doSignal(sigid & SIGNAL_ID_MASK, SIGNAL_RED);
}
if (compileFeatures & FEATURE_SIGNAL) {
onRedLookup=LookListLoader(OPCODE_ONRED);
onAmberLookup=LookListLoader(OPCODE_ONAMBER);
onGreenLookup=LookListLoader(OPCODE_ONGREEN);
for (int sigslot=0;;sigslot++) {
int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8);
if (sighandle==0) break; // end of signal list
VPIN sigid = sighandle & SIGNAL_ID_MASK;
doSignal(sigid, SIGNAL_RED);
}
}
int progCounter;
@ -225,7 +228,6 @@ if (compileFeatures & FEATURE_SIGNAL) {
case OPCODE_AT:
case OPCODE_ATTIMEOUT2:
case OPCODE_AFTER:
case OPCODE_AFTEROVERLOAD:
case OPCODE_IF:
case OPCODE_IFNOT: {
int16_t pin = (int16_t)operand;
@ -251,6 +253,14 @@ if (compileFeatures & FEATURE_SIGNAL) {
break;
}
case OPCODE_ONSENSOR:
if (compileFeatures & FEATURE_SENSOR)
new EXRAILSensor(operand,progCounter+3,true );
break;
case OPCODE_ONBUTTON:
if (compileFeatures & FEATURE_SENSOR)
new EXRAILSensor(operand,progCounter+3,false );
break;
case OPCODE_TURNOUT: {
VPIN id=operand;
int addr=getOperand(progCounter,1);
@ -373,7 +383,7 @@ RMFT2::RMFT2(int progCtr) {
speedo=0;
forward=true;
invert=false;
timeoutFlag=false;
blinkState=not_blink_task;
stackDepth=0;
onEventStartPosition=-1; // Not handling an ONxxx
@ -411,7 +421,7 @@ void RMFT2::createNewTask(int route, uint16_t cab) {
void RMFT2::driveLoco(byte speed) {
if (loco<=0) return; // Prevent broadcast!
if (diag) DIAG(F("EXRAIL drive %d %d %d"),loco,speed,forward^invert);
//if (diag) DIAG(F("EXRAIL drive %d %d %d"),loco,speed,forward^invert);
/* TODO.....
power on appropriate track if DC or main if dcc
if (TrackManager::getMainPowerMode()==POWERMODE::OFF) {
@ -480,6 +490,8 @@ bool RMFT2::skipIfBlock() {
}
void RMFT2::loop() {
if (compileFeatures & FEATURE_SENSOR)
EXRAILSensor::checkAll();
// Round Robin call to a RMFT task each time
if (loopTask==NULL) return;
@ -491,6 +503,23 @@ void RMFT2::loop() {
void RMFT2::loop2() {
if (delayTime!=0 && millis()-delayStart < delayTime) return;
// special stand alone blink task
if (compileFeatures & FEATURE_BLINK) {
if (blinkState==blink_low) {
IODevice::write(blinkPin,HIGH);
blinkState=blink_high;
delayMe(getOperand(1));
return;
}
if (blinkState==blink_high) {
IODevice::write(blinkPin,LOW);
blinkState=blink_low;
delayMe(getOperand(2));
return;
}
}
// Normal progstep following tasks continue here.
byte opcode = GET_OPCODE;
int16_t operand = getOperand(0);
@ -511,6 +540,10 @@ void RMFT2::loop2() {
Turnout::setClosed(operand, true);
break;
case OPCODE_TOGGLE_TURNOUT:
Turnout::setClosed(operand, Turnout::isThrown(operand));
break;
#ifndef IO_NO_HAL
case OPCODE_ROTATE:
uint8_t activity;
@ -560,49 +593,51 @@ void RMFT2::loop2() {
break;
case OPCODE_AT:
timeoutFlag=false;
blinkState=not_blink_task;
if (readSensor(operand)) break;
delayMe(50);
return;
case OPCODE_ATGTE: // wait for analog sensor>= value
timeoutFlag=false;
blinkState=not_blink_task;
if (IODevice::readAnalogue(operand) >= (int)(getOperand(1))) break;
delayMe(50);
return;
case OPCODE_ATLT: // wait for analog sensor < value
timeoutFlag=false;
blinkState=not_blink_task;
if (IODevice::readAnalogue(operand) < (int)(getOperand(1))) break;
delayMe(50);
return;
case OPCODE_ATTIMEOUT1: // ATTIMEOUT(vpin,timeout) part 1
timeoutStart=millis();
timeoutFlag=false;
blinkState=not_blink_task;
break;
case OPCODE_ATTIMEOUT2:
if (readSensor(operand)) break; // success without timeout
if (millis()-timeoutStart > 100*getOperand(1)) {
timeoutFlag=true;
blinkState=at_timeout;
break; // and drop through
}
delayMe(50);
return;
case OPCODE_IFTIMEOUT: // do next operand if timeout flag set
skipIf=!timeoutFlag;
skipIf=blinkState!=at_timeout;
break;
case OPCODE_AFTER: // waits for sensor to hit and then remain off for 0.5 seconds. (must come after an AT operation)
case OPCODE_AFTER: // waits for sensor to hit and then remain off for x mS.
// Note, this must come after an AT operation, which is
// automatically inserted by the AFTER macro.
if (readSensor(operand)) {
// reset timer to half a second and keep waiting
// reset timer and keep waiting
waitAfter=millis();
delayMe(50);
return;
}
if (millis()-waitAfter < 500 ) return;
if (millis()-waitAfter < getOperand(1) ) return;
break;
case OPCODE_AFTEROVERLOAD: // waits for the power to be turned back on - either by power routine or button
@ -624,13 +659,25 @@ void RMFT2::loop2() {
break;
case OPCODE_SET:
killBlinkOnVpin(operand);
IODevice::write(operand,true);
break;
case OPCODE_RESET:
killBlinkOnVpin(operand);
IODevice::write(operand,false);
break;
case OPCODE_BLINK:
// Start a new task to blink this vpin
killBlinkOnVpin(operand);
{
auto newtask=new RMFT2(progCounter);
newtask->blinkPin=operand;
newtask->blinkState=blink_low; // will go high on first call
}
break;
case OPCODE_PAUSE:
DCC::setThrottle(0,1,true); // pause all locos on the track
pausingTask=this;
@ -671,41 +718,7 @@ void RMFT2::loop2() {
case OPCODE_SETFREQ:
// Frequency is default 0, or 1, 2,3
//if (loco) DCC::setFn(loco,operand,true);
switch (operand) {
case 0: // default - all F-s off
if (loco) {
DCC::setFn(loco,29,false);
DCC::setFn(loco,30,false);
DCC::setFn(loco,31,false);
}
break;
case 1:
if (loco) {
DCC::setFn(loco,29,true);
DCC::setFn(loco,30,false);
DCC::setFn(loco,31,false);
}
break;
case 2:
if (loco) {
DCC::setFn(loco,29,false);
DCC::setFn(loco,30,true);
DCC::setFn(loco,31,false);
}
break;
case 3:
if (loco) {
DCC::setFn(loco,29,false);
DCC::setFn(loco,30,false);
DCC::setFn(loco,31,true);
}
break;
default:
; // do nothing
break;
}
DCC::setDCFreq(loco,operand);
break;
case OPCODE_RESUME:
@ -815,6 +828,10 @@ void RMFT2::loop2() {
case OPCODE_FOFF:
if (loco) DCC::setFn(loco,operand,false);
break;
case OPCODE_FTOGGLE:
if (loco) DCC::changeFn(loco,operand);
break;
case OPCODE_DRIVE:
{
@ -830,6 +847,10 @@ void RMFT2::loop2() {
case OPCODE_XFOFF:
DCC::setFn(operand,getOperand(1),false);
break;
case OPCODE_XFTOGGLE:
DCC::changeFn(operand,getOperand(1));
break;
case OPCODE_DCCACTIVATE: {
// operand is address<<3 | subaddr<<1 | active
@ -947,6 +968,14 @@ void RMFT2::loop2() {
if ((compileFeatures & FEATURE_LCC) && LCCSerial)
StringFormatter::send(LCCSerial,F("<L x%h>"),(uint16_t)operand);
break;
case OPCODE_ACON: // MERG adapter
case OPCODE_ACOF:
if ((compileFeatures & FEATURE_LCC) && LCCSerial)
StringFormatter::send(LCCSerial,F("<L x%c%h%h>"),
opcode==OPCODE_ACON?'0':'1',
(uint16_t)operand,getOperand(progCounter,1));
break;
case OPCODE_LCCX: // long form LCC
if ((compileFeatures & FEATURE_LCC) && LCCSerial)
@ -1029,7 +1058,7 @@ void RMFT2::loop2() {
case OPCODE_ROUTE:
case OPCODE_AUTOMATION:
case OPCODE_SEQUENCE:
if (diag) DIAG(F("EXRAIL begin(%d)"),operand);
//if (diag) DIAG(F("EXRAIL begin(%d)"),operand);
break;
case OPCODE_AUTOSTART: // Handled only during begin process
@ -1039,6 +1068,8 @@ void RMFT2::loop2() {
case OPCODE_PINTURNOUT: // Turnout definition ignored at runtime
case OPCODE_ONCLOSE: // Turnout event catchers ignored here
case OPCODE_ONLCC: // LCC event catchers ignored here
case OPCODE_ONACON: // MERG event catchers ignored here
case OPCODE_ONACOF: // MERG event catchers ignored here
case OPCODE_ONTHROW:
case OPCODE_ONACTIVATE: // Activate event catchers ignored here
case OPCODE_ONDEACTIVATE:
@ -1047,6 +1078,8 @@ void RMFT2::loop2() {
case OPCODE_ONGREEN:
case OPCODE_ONCHANGE:
case OPCODE_ONTIME:
case OPCODE_ONBUTTON:
case OPCODE_ONSENSOR:
#ifndef IO_NO_HAL
case OPCODE_DCCTURNTABLE: // Turntable definition ignored at runtime
case OPCODE_EXTTTURNTABLE: // Turntable definition ignored at runtime
@ -1092,24 +1125,30 @@ void RMFT2::kill(const FSH * reason, int operand) {
}
int16_t RMFT2::getSignalSlot(int16_t id) {
for (int sigslot=0;;sigslot++) {
int16_t sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8);
if (sigid==0) { // end of signal list
DIAG(F("EXRAIL Signal %d not defined"), id);
return -1;
}
if (id > 0) {
int sigslot = 0;
int16_t sighandle = 0;
// Trundle down the signal list until we reach the end
while ((sighandle = GETHIGHFLASHW(RMFT2::SignalDefinitions, sigslot * 8)) != 0)
{
// sigid is the signal id used in RED/AMBER/GREEN macro
// for a LED signal it will be same as redpin
// but for a servo signal it will also have SERVO_SIGNAL_FLAG set.
if ((sigid & SIGNAL_ID_MASK)!= id) continue; // keep looking
return sigslot; // relative slot in signals table
}
// but for a servo signal it will also have SERVO_SIGNAL_FLAG set.
VPIN sigid = sighandle & SIGNAL_ID_MASK;
if (sigid == (VPIN)id) // cast to keep compiler happy but id is positive
return sigslot; // found it
sigslot++; // keep looking
};
}
// If we got here, we did not find the signal
DIAG(F("EXRAIL Signal %d not defined"), id);
return -1;
}
/* static */ void RMFT2::doSignal(int16_t id,char rag) {
if (!(compileFeatures & FEATURE_SIGNAL)) return; // dont compile code below
if (diag) DIAG(F(" doSignal %d %x"),id,rag);
//if (diag) DIAG(F(" doSignal %d %x"),id,rag);
// Schedule any event handler for this signal change.
// This will work even without a signal definition.
@ -1125,19 +1164,20 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
// Correct signal definition found, get the rag values
int16_t sigpos=sigslot*8;
VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos);
int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos);
VPIN redpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+2);
VPIN amberpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+4);
VPIN greenpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+6);
if (diag) DIAG(F("signal %d %d %d %d %d"),sigid,id,redpin,amberpin,greenpin);
//if (diag) DIAG(F("signal %d %d %d %d %d"),sigid,id,redpin,amberpin,greenpin);
VPIN sigtype=sigid & ~SIGNAL_ID_MASK;
VPIN sigtype=sighandle & ~SIGNAL_ID_MASK;
VPIN sigid = sighandle & SIGNAL_ID_MASK;
if (sigtype == SERVO_SIGNAL_FLAG) {
// A servo signal, the pin numbers are actually servo positions
// Note, setting a signal to a zero position has no effect.
int16_t servopos= rag==SIGNAL_RED? redpin: (rag==SIGNAL_GREEN? greenpin : amberpin);
if (diag) DIAG(F("sigA %d %d"),id,servopos);
//if (diag) DIAG(F("sigA %d %d"),id,servopos);
if (servopos!=0) IODevice::writeAnalogue(id,servopos,PCA9685::Bounce);
return;
}
@ -1154,7 +1194,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
byte value=redpin;
if (rag==SIGNAL_AMBER) value=amberpin;
if (rag==SIGNAL_GREEN) value=greenpin;
DCC::setExtendedAccessory(sigid & SIGNAL_ID_MASK,value);
DCC::setExtendedAccessory(sigid, value);
return;
}
@ -1174,22 +1214,25 @@ if (sigtype== NEOPIXEL_SIGNAL_FLAG) {
if (rag==SIGNAL_AMBER && (amberpin==0)) rag=SIMAMBER; // special case this func only
// Manage invert (HIGH on) pins
bool aHigh=sigid & ACTIVE_HIGH_SIGNAL_FLAG;
bool aHigh=sighandle & ACTIVE_HIGH_SIGNAL_FLAG;
// set the three pins
if (redpin) {
bool redval=(rag==SIGNAL_RED || rag==SIMAMBER);
if (!aHigh) redval=!redval;
killBlinkOnVpin(redpin);
IODevice::write(redpin,redval);
}
if (amberpin) {
bool amberval=(rag==SIGNAL_AMBER);
if (!aHigh) amberval=!amberval;
killBlinkOnVpin(amberpin);
IODevice::write(amberpin,amberval);
}
if (greenpin) {
bool greenval=(rag==SIGNAL_GREEN || rag==SIMAMBER);
if (!aHigh) greenval=!greenval;
killBlinkOnVpin(greenpin);
IODevice::write(greenpin,greenval);
}
}
@ -1211,8 +1254,9 @@ bool RMFT2::signalAspectEvent(int16_t address, byte aspect ) {
int16_t sigslot=getSignalSlot(address);
if (sigslot<0) return false; // this is not a defined signal
int16_t sigpos=sigslot*8;
VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos);
VPIN sigtype=sigid & ~SIGNAL_ID_MASK;
int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos);
VPIN sigtype=sighandle & ~SIGNAL_ID_MASK;
VPIN sigid = sighandle & SIGNAL_ID_MASK;
if (sigtype!=DCCX_SIGNAL_FLAG) return false; // not a DCCX signal
// Turn an aspect change into a RED/AMBER/GREEN setting
if (aspect==GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+2)) {
@ -1261,7 +1305,7 @@ void RMFT2::rotateEvent(int16_t turntableId, bool change) {
void RMFT2::clockEvent(int16_t clocktime, bool change) {
// Hunt for an ONTIME for this time
if (Diag::CMD)
DIAG(F("Looking for clock event at : %d"), clocktime);
DIAG(F("clockEvent at : %d"), clocktime);
if (change) {
onClockLookup->handleEvent(F("CLOCK"),clocktime);
onClockLookup->handleEvent(F("CLOCK"),25*60+clocktime%60);
@ -1271,12 +1315,31 @@ void RMFT2::clockEvent(int16_t clocktime, bool change) {
void RMFT2::powerEvent(int16_t track, bool overload) {
// Hunt for an ONOVERLOAD for this item
if (Diag::CMD)
DIAG(F("Looking for Power event on track : %c"), track);
DIAG(F("powerEvent : %c"), track);
if (overload) {
onOverloadLookup->handleEvent(F("POWER"),track);
}
}
// This function is used when setting pins so that a SET or RESET
// will cause any blink task on that pin to terminate.
// It will be compiled out of existence if no BLINK feature is used.
void RMFT2::killBlinkOnVpin(VPIN pin) {
if (!(compileFeatures & FEATURE_BLINK)) return;
RMFT2 * task=loopTask;
while(task) {
if (
(task->blinkState==blink_high || task->blinkState==blink_low)
&& task->blinkPin==pin) {
task->kill();
return;
}
task=task->next;
if (task==loopTask) return;
}
}
void RMFT2::startNonRecursiveTask(const FSH* reason, int16_t id,int pc) {
// Check we dont already have a task running this handler
RMFT2 * task=loopTask;
@ -1347,6 +1410,7 @@ void RMFT2::thrungeString(uint32_t strfar, thrunger mode, byte id) {
break;
case thrunge_parse:
case thrunge_broadcast:
case thrunge_message:
case thrunge_lcd:
default: // thrunge_lcd+1, ...
if (!buffer) buffer=new StringBuffer();
@ -1384,6 +1448,9 @@ void RMFT2::thrungeString(uint32_t strfar, thrunger mode, byte id) {
case thrunge_withrottle:
CommandDistributor::broadcastRaw(CommandDistributor::WITHROTTLE_TYPE,buffer->getString());
break;
case thrunge_message:
CommandDistributor::broadcastMessage(buffer->getString());
break;
case thrunge_lcd:
LCD(id,F("%s"),buffer->getString());
break;

View File

@ -33,7 +33,7 @@
// or more OPCODE_PAD instructions with the subsequent parameters. This wastes a byte but makes
// searching easier as a parameter can never be confused with an opcode.
//
enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,
enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,OPCODE_TOGGLE_TURNOUT,
OPCODE_FWD,OPCODE_REV,OPCODE_SPEED,OPCODE_INVERT_DIRECTION,
OPCODE_RESERVE,OPCODE_FREE,
OPCODE_AT,OPCODE_AFTER,
@ -41,9 +41,11 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,
OPCODE_ATGTE,OPCODE_ATLT,
OPCODE_ATTIMEOUT1,OPCODE_ATTIMEOUT2,
OPCODE_LATCH,OPCODE_UNLATCH,OPCODE_SET,OPCODE_RESET,
OPCODE_BLINK,
OPCODE_ENDIF,OPCODE_ELSE,
OPCODE_DELAY,OPCODE_DELAYMINS,OPCODE_DELAYMS,OPCODE_RANDWAIT,
OPCODE_FON,OPCODE_FOFF,OPCODE_XFON,OPCODE_XFOFF,
OPCODE_FTOGGLE,OPCODE_XFTOGGLE,
OPCODE_RED,OPCODE_GREEN,OPCODE_AMBER,OPCODE_DRIVE,
OPCODE_SERVO,OPCODE_SIGNAL,OPCODE_TURNOUT,OPCODE_WAITFOR,
OPCODE_PAD,OPCODE_FOLLOW,OPCODE_CALL,OPCODE_RETURN,
@ -67,10 +69,13 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,
OPCODE_TTADDPOSITION,OPCODE_DCCTURNTABLE,OPCODE_EXTTTURNTABLE,
OPCODE_ONROTATE,OPCODE_ROTATE,OPCODE_WAITFORTT,
OPCODE_LCC,OPCODE_LCCX,OPCODE_ONLCC,
OPCODE_ACON, OPCODE_ACOF,
OPCODE_ONACON, OPCODE_ONACOF,
OPCODE_ONOVERLOAD,
OPCODE_ROUTE_ACTIVE,OPCODE_ROUTE_INACTIVE,OPCODE_ROUTE_HIDDEN,
OPCODE_ROUTE_DISABLED,
OPCODE_STASH,OPCODE_CLEAR_STASH,OPCODE_CLEAR_ALL_STASH,OPCODE_PICKUP_STASH,
OPCODE_ONBUTTON,OPCODE_ONSENSOR,
OPCODE_NEOPIXEL,
// OPcodes below this point are skip-nesting IF operations
// placed here so that they may be skipped as a group
@ -94,16 +99,26 @@ enum thrunger: byte {
thrunge_serial,thrunge_parse,
thrunge_serial1, thrunge_serial2, thrunge_serial3,
thrunge_serial4, thrunge_serial5, thrunge_serial6,
thrunge_lcn,
thrunge_lcn,thrunge_message,
thrunge_lcd, // Must be last!!
};
enum BlinkState: byte {
not_blink_task,
blink_low, // blink task running with pin LOW
blink_high, // blink task running with pin high
at_timeout // ATTIMEOUT timed out flag
};
// Flag bits for compile time features.
static const byte FEATURE_SIGNAL= 0x80;
static const byte FEATURE_LCC = 0x40;
static const byte FEATURE_ROSTER= 0x20;
static const byte FEATURE_ROUTESTATE= 0x10;
static const byte FEATURE_STASH = 0x08;
static const byte FEATURE_BLINK = 0x04;
static const byte FEATURE_SENSOR = 0x02;
// Flag bits for status of hardware and TPL
@ -177,7 +192,9 @@ class LookList {
static const FSH * getTurntableDescription(int16_t id);
static const FSH * getTurntablePositionDescription(int16_t turntableId, uint8_t positionId);
static void startNonRecursiveTask(const FSH* reason, int16_t id,int pc);
static bool readSensor(uint16_t sensorId);
static bool isSignal(int16_t id,char rag);
private:
static void ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]);
static bool parseSlash(Print * stream, byte & paramCount, int16_t p[]) ;
@ -186,7 +203,6 @@ private:
static bool getFlag(VPIN id,byte mask);
static int16_t progtrackLocoId;
static void doSignal(int16_t id,char rag);
static bool isSignal(int16_t id,char rag);
static int16_t getSignalSlot(int16_t id);
static void setTurnoutHiddenState(Turnout * t);
#ifndef IO_NO_HAL
@ -195,11 +211,11 @@ private:
static LookList* LookListLoader(OPCODE op1,
OPCODE op2=OPCODE_ENDEXRAIL,OPCODE op3=OPCODE_ENDEXRAIL);
static uint16_t getOperand(int progCounter,byte n);
static void killBlinkOnVpin(VPIN pin);
static RMFT2 * loopTask;
static RMFT2 * pausingTask;
void delayMe(long millisecs);
void driveLoco(byte speedo);
bool readSensor(uint16_t sensorId);
bool skipIfBlock();
bool readLoco();
void loop2();
@ -247,10 +263,10 @@ private:
union {
unsigned long waitAfter; // Used by OPCODE_AFTER
unsigned long timeoutStart; // Used by OPCODE_ATTIMEOUT
VPIN blinkPin; // Used by blink tasks
};
bool timeoutFlag;
byte taskId;
BlinkState blinkState; // includes AT_TIMEOUT flag.
uint16_t loco;
bool forward;
bool invert;

View File

@ -38,6 +38,7 @@
#undef ATTIMEOUT
#undef AUTOMATION
#undef AUTOSTART
#undef BLINK
#undef BROADCAST
#undef CALL
#undef CLEAR_STASH
@ -66,6 +67,7 @@
#undef FOLLOW
#undef FON
#undef FORGET
#undef FTOGGLE
#undef FREE
#undef FWD
#undef GREEN
@ -100,6 +102,11 @@
#undef NEOPIXEL
#undef NEOPIXEL_OFF
#undef NEOPIXEL_SIGNAL
#undef ACON
#undef ACOF
#undef ONACON
#undef ONACOF
#undef MESSAGE
#undef ONACTIVATE
#undef ONACTIVATEL
#undef ONAMBER
@ -114,6 +121,8 @@
#undef ONGREEN
#undef ONRED
#undef ONROTATE
#undef ONBUTTON
#undef ONSENSOR
#undef ONTHROW
#undef ONCHANGE
#undef PARSE
@ -166,8 +175,10 @@
#undef START
#undef STASH
#undef STEALTH
#undef STEALTH_GLOBAL
#undef STOP
#undef THROW
#undef TOGGLE_TURNOUT
#undef TT_ADDPOSITION
#undef TURNOUT
#undef TURNOUTL
@ -182,11 +193,12 @@
#undef WITHROTTLE
#undef XFOFF
#undef XFON
#undef XFTOGGLE
#ifndef RMFT2_UNDEF_ONLY
#define ACTIVATE(addr,subaddr)
#define ACTIVATEL(addr)
#define AFTER(sensor_id)
#define AFTER(sensor_id,timer...)
#define AFTEROVERLOAD(track_id)
#define ALIAS(name,value...)
#define AMBER(signal_id)
@ -198,6 +210,7 @@
#define ATTIMEOUT(sensor_id,timeout_ms)
#define AUTOMATION(id,description)
#define AUTOSTART
#define BLINK(vpin,onDuty,offDuty)
#define BROADCAST(msg)
#define CALL(route)
#define CLEAR_STASH(id)
@ -227,6 +240,7 @@
#define FON(func)
#define FORGET
#define FREE(blockid)
#define FTOGGLE(func)
#define FWD(speed)
#define GREEN(signal_id)
#define HAL(haltype,params...)
@ -256,10 +270,15 @@
#define LCD(row,msg)
#define SCREEN(display,row,msg)
#define LCN(msg)
#define MESSAGE(msg)
#define MOVETT(id,steps,activity)
#define NEOPIXEL(id,colour)
#define NEOPIXEL_OFF(id,colour)
#define NEOPIXEL_SIGNAL(sigid,redcolour,ambercolour,greencolour)
#define ACON(eventid)
#define ACOF(eventid)
#define ONACON(eventid)
#define ONACOF(eventid)
#define ONACTIVATE(addr,subaddr)
#define ONACTIVATEL(linear)
#define ONAMBER(signal_id)
@ -276,6 +295,8 @@
#define ONROTATE(turntable_id)
#define ONTHROW(turnout_id)
#define ONCHANGE(sensor_id)
#define ONSENSOR(sensor_id)
#define ONBUTTON(sensor_id)
#define PAUSE
#define PIN_TURNOUT(id,pin,description...)
#define PRINT(msg)
@ -319,15 +340,17 @@
#define SET_TRACK(track,mode)
#define SET_POWER(track,onoff)
#define SETLOCO(loco)
#define SETFREQ(loco,freq)
#define SETFREQ(freq)
#define SIGNAL(redpin,amberpin,greenpin)
#define SIGNALH(redpin,amberpin,greenpin)
#define SPEED(speed)
#define START(route)
#define STASH(id)
#define STEALTH(code...)
#define STEALTH_GLOBAL(code...)
#define STOP
#define THROW(id)
#define TOGGLE_TURNOUT(id)
#define TT_ADDPOSITION(turntable_id,position,value,angle,description...)
#define TURNOUT(id,addr,subaddr,description...)
#define TURNOUTL(id,addr,description...)
@ -342,4 +365,6 @@
#define WITHROTTLE(msg)
#define XFOFF(cab,func)
#define XFON(cab,func)
#define XFTOGGLE(cab,func)
#endif

View File

@ -36,7 +36,7 @@
void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]) {
(void)stream; // avoid compiler warning if we don't access this parameter
bool reject=false;
switch(opcode) {
case 'D':
@ -47,8 +47,7 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16
break;
case '/': // New EXRAIL command
reject=!parseSlash(stream,paramCount,p);
opcode=0;
if (parseSlash(stream,paramCount,p)) opcode=0;
break;
case 'A': // <A address aspect>
@ -62,53 +61,93 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16
case 'L':
// This entire code block is compiled out if LLC macros not used
if (!(compileFeatures & FEATURE_LCC)) return;
static int lccProgCounter=0;
static int lccEventIndex=0;
if (paramCount==0) { //<L> LCC adapter introducing self
LCCSerial=stream; // now we know where to send events we raise
opcode=0; // flag command as intercepted
// loop through all possible sent events
for (int progCounter=0;; SKIPOP) {
byte opcode=GET_OPCODE;
if (opcode==OPCODE_ENDEXRAIL) break;
if (opcode==OPCODE_LCC) StringFormatter::send(stream,F("<LS x%h>\n"),getOperand(progCounter,0));
if (opcode==OPCODE_LCCX) { // long form LCC
StringFormatter::send(stream,F("<LS x%h%h%h%h>\n"),
// loop through all possible sent/waited events
for (int progCounter=lccProgCounter;; SKIPOP) {
byte exrailOpcode=GET_OPCODE;
switch (exrailOpcode) {
case OPCODE_ENDEXRAIL:
stream->print(F("<LR>\n")); // ready to roll
lccProgCounter=0; // allow a second pass
lccEventIndex=0;
return;
case OPCODE_LCC:
StringFormatter::send(stream,F("<LS x%h>\n"),getOperand(progCounter,0));
SKIPOP;
lccProgCounter=progCounter;
return;
case OPCODE_LCCX: // long form LCC
StringFormatter::send(stream,F("<LS x%h%h%h%h>\n"),
getOperand(progCounter,1),
getOperand(progCounter,2),
getOperand(progCounter,3),
getOperand(progCounter,0)
);
}}
);
SKIPOP;SKIPOP;SKIPOP;SKIPOP;
lccProgCounter=progCounter;
return;
case OPCODE_ACON: // CBUS ACON
case OPCODE_ACOF: // CBUS ACOF
StringFormatter::send(stream,F("<LS x%c%h%h>\n"),
exrailOpcode==OPCODE_ACOF?'1':'0',
getOperand(progCounter,0),getOperand(progCounter,1));
SKIPOP;SKIPOP;
lccProgCounter=progCounter;
return;
// we stream the hex events we wish to listen to
// and at the same time build the event index looku.
int eventIndex=0;
for (int progCounter=0;; SKIPOP) {
byte opcode=GET_OPCODE;
if (opcode==OPCODE_ENDEXRAIL) break;
if (opcode==OPCODE_ONLCC) {
onLCCLookup[eventIndex]=progCounter; // TODO skip...
case OPCODE_ONLCC:
StringFormatter::send(stream,F("<LL %d x%h%h%h:%h>\n"),
eventIndex,
lccEventIndex,
getOperand(progCounter,1),
getOperand(progCounter,2),
getOperand(progCounter,3),
getOperand(progCounter,0)
);
eventIndex++;
}
SKIPOP;SKIPOP;SKIPOP;SKIPOP;
// start on handler at next
onLCCLookup[lccEventIndex]=progCounter;
lccEventIndex++;
lccProgCounter=progCounter;
return;
case OPCODE_ONACON:
case OPCODE_ONACOF:
StringFormatter::send(stream,F("<LL %d x%c%h%h>\n"),
lccEventIndex,
exrailOpcode==OPCODE_ONACOF?'1':'0',
getOperand(progCounter,0),getOperand(progCounter,1)
);
SKIPOP;SKIPOP;
// start on handler at next
onLCCLookup[lccEventIndex]=progCounter;
lccEventIndex++;
lccProgCounter=progCounter;
return;
default:
break;
}
}
StringFormatter::send(stream,F("<LR>\n")); // Ready to rumble
opcode=0;
break;
}
if (paramCount==1) { // <L eventid> LCC event arrived from adapter
int16_t eventid=p[0];
reject=eventid<0 || eventid>=countLCCLookup;
if (!reject) startNonRecursiveTask(F("LCC"),eventid,onLCCLookup[eventid]);
opcode=0;
bool reject = eventid<0 || eventid>=countLCCLookup;
if (!reject) {
startNonRecursiveTask(F("LCC"),eventid,onLCCLookup[eventid]);
opcode=0;
}
}
break;
@ -182,12 +221,20 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) {
StringFormatter::send(stream, F("<* EXRAIL STATUS"));
RMFT2 * task=loopTask;
while(task) {
if ((compileFeatures & FEATURE_BLINK)
&& (task->blinkState==blink_high || task->blinkState==blink_low)) {
StringFormatter::send(stream,F("\nID=%d,PC=%d,BLINK=%d"),
(int)(task->taskId),task->progCounter,task->blinkPin
);
}
else {
StringFormatter::send(stream,F("\nID=%d,PC=%d,LOCO=%d%c,SPEED=%d%c"),
(int)(task->taskId),task->progCounter,task->loco,
task->invert?'I':' ',
task->speedo,
task->forward?'F':'R'
);
}
task=task->next;
if (task==loopTask) break;
}
@ -205,12 +252,13 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) {
// do the signals
// flags[n] represents the state of the nth signal in the table
for (int sigslot=0;;sigslot++) {
VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8);
if (sigid==0) break; // end of signal list
byte flag=flags[sigslot] & SIGNAL_MASK; // obtain signal flags for this id
int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8);
if (sighandle==0) break; // end of signal list
VPIN sigid = sighandle & SIGNAL_ID_MASK;
byte flag=flags[sigslot] & SIGNAL_MASK; // obtain signal flags for this id
StringFormatter::send(stream,F("\n%S[%d]"),
(flag == SIGNAL_RED)? F("RED") : (flag==SIGNAL_GREEN) ? F("GREEN") : F("AMBER"),
sigid & SIGNAL_ID_MASK);
(flag == SIGNAL_RED)? F("RED") : (flag==SIGNAL_GREEN) ? F("GREEN") : F("AMBER"),
sigid);
}
}

View File

@ -75,7 +75,7 @@
// Pass 1 Implements aliases
#include "EXRAIL2MacroReset.h"
#undef ALIAS
#define ALIAS(name,value...) const int name= 1##value##0 ==10 ? -__COUNTER__ : value##0/10;
#define ALIAS(name,value...) const int name= #value[0] ? value+0: -__COUNTER__ ;
#include "myAutomation.h"
// Pass 1d Detect sequence duplicates.
@ -95,14 +95,14 @@ constexpr int16_t stuffSize=sizeof(compileTimeSequenceList)/sizeof(int16_t) - 1;
// Compile time function to check for sequence nos.
constexpr bool hasseq(const int16_t value, const uint16_t pos=0 ) {
constexpr bool hasseq(const int16_t value, const int16_t pos=0 ) {
return pos>=stuffSize? false :
compileTimeSequenceList[pos]==value
|| hasseq(value,pos+1);
}
// Compile time function to check for duplicate sequence nos.
constexpr bool hasdup(const int16_t value, const uint16_t pos ) {
constexpr bool hasdup(const int16_t value, const int16_t pos ) {
return pos>=stuffSize? false :
compileTimeSequenceList[pos]==value
|| hasseq(value,pos+1)
@ -145,6 +145,12 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU
#include "myAutomation.h"
// Pass 1g Implants STEALTH_GLOBAL in correct place
#include "EXRAIL2MacroReset.h"
#undef STEALTH_GLOBAL
#define STEALTH_GLOBAL(code...) code
#include "myAutomation.h"
// Pass 1h Implements HAL macro by creating exrailHalSetup function
// Also allows creating EXTurntable object
#include "EXRAIL2MacroReset.h"
@ -185,6 +191,14 @@ bool exrailHalSetup() {
#define LCCX(senderid,eventid) | FEATURE_LCC
#undef ONLCC
#define ONLCC(senderid,eventid) | FEATURE_LCC
#undef ACON
#define ACON(eventid) | FEATURE_LCC
#undef ACOF
#define ACOF(eventid) | FEATURE_LCC
#undef ONACON
#define ONACON(eventid) | FEATURE_LCC
#undef ONACOF
#define ONACOF(eventid) | FEATURE_LCC
#undef ROUTE_ACTIVE
#define ROUTE_ACTIVE(id) | FEATURE_ROUTESTATE
#undef ROUTE_INACTIVE
@ -204,6 +218,12 @@ bool exrailHalSetup() {
#define PICKUP_STASH(id) | FEATURE_STASH
#undef STASH
#define STASH(id) | FEATURE_STASH
#undef BLINK
#define BLINK(vpin,onDuty,offDuty) | FEATURE_BLINK
#undef ONBUTTON
#define ONBUTTON(vpin) | FEATURE_SENSOR
#undef ONSENSOR
#define ONSENSOR(vpin) | FEATURE_SENSOR
const byte RMFT2::compileFeatures = 0
#include "myAutomation.h"
@ -255,6 +275,9 @@ const int StringMacroTracker1=__COUNTER__;
#define PRINT(msg) THRUNGE(msg,thrunge_print)
#undef LCN
#define LCN(msg) THRUNGE(msg,thrunge_lcn)
#undef MESSAGE
#define MESSAGE(msg) THRUNGE(msg,thrunge_message)
#undef ROUTE_CAPTION
#define ROUTE_CAPTION(id,caption) \
case (__COUNTER__ - StringMacroTracker1) : {\
@ -352,6 +375,8 @@ const FSH * RMFT2::getTurntableDescription(int16_t turntableId) {
#define TT_ADDPOSITION(turntable_id,position,value,home,description...) T_DESC(turntable_id,position,description)
const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) {
(void)turntableId;
(void)positionId;
#include "myAutomation.h"
return NULL;
}
@ -416,10 +441,14 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = {
#include "myAutomation.h"
0,0,0,0 };
// Pass 9 ONLCC counter and lookup array
// Pass 9 ONLCC/ ONMERG counter and lookup array
#include "EXRAIL2MacroReset.h"
#undef ONLCC
#define ONLCC(sender,event) +1
#undef ONACON
#define ONACON(event) +1
#undef ONACOF
#define ONACOF(event) +1
const int RMFT2::countLCCLookup=0
#include "myAutomation.h"
@ -438,7 +467,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define ACTIVATE(addr,subaddr) OPCODE_DCCACTIVATE,V(addr<<3 | subaddr<<1 | 1),
#define ACTIVATEL(addr) OPCODE_DCCACTIVATE,V((addr+3)<<1 | 1),
#define AFTER(sensor_id) OPCODE_AT,V(sensor_id),OPCODE_AFTER,V(sensor_id),
#define AFTER(sensor_id,timer...) OPCODE_AT,V(sensor_id),OPCODE_AFTER,V(sensor_id),OPCODE_PAD,V(#timer[0]?timer+0:500),
#define AFTEROVERLOAD(track_id) OPCODE_AFTEROVERLOAD,V(TRACK_NUMBER_##track_id),
#define ALIAS(name,value...)
#define AMBER(signal_id) OPCODE_AMBER,V(signal_id),
@ -450,6 +479,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define ATTIMEOUT(sensor_id,timeout) OPCODE_ATTIMEOUT1,0,0,OPCODE_ATTIMEOUT2,V(sensor_id),OPCODE_PAD,V(timeout/100L),
#define AUTOMATION(id, description) OPCODE_AUTOMATION, V(id),
#define AUTOSTART OPCODE_AUTOSTART,0,0,
#define BLINK(vpin,onDuty,offDuty) OPCODE_BLINK,V(vpin),OPCODE_PAD,V(onDuty),OPCODE_PAD,V(offDuty),
#define BROADCAST(msg) PRINT(msg)
#define CALL(route) OPCODE_CALL,V(route),
#define CLEAR_STASH(id) OPCODE_CLEAR_STASH,V(id),
@ -483,6 +513,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define FON(func) OPCODE_FON,V(func),
#define FORGET OPCODE_FORGET,0,0,
#define FREE(blockid) OPCODE_FREE,V(blockid),
#define FTOGGLE(func) OPCODE_FTOGGLE,V(func),
#define FWD(speed) OPCODE_FWD,V(speed),
#define GREEN(signal_id) OPCODE_GREEN,V(signal_id),
#define HAL(haltype,params...)
@ -514,10 +545,16 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
OPCODE_PAD,V((((uint64_t)sender)>>32)&0xFFFF),\
OPCODE_PAD,V((((uint64_t)sender)>>16)&0xFFFF),\
OPCODE_PAD,V((((uint64_t)sender)>>0)&0xFFFF),
#define ACON(eventid) OPCODE_ACON,V(((uint32_t)eventid >>16) & 0xFFFF),OPCODE_PAD,V(eventid & 0xFFFF),
#define ACOF(eventid) OPCODE_ACOF,V(((uint32_t)eventid >>16) & 0xFFFF),OPCODE_PAD,V(eventid & 0xFFFF),
#define ONACON(eventid) OPCODE_ONACON,V((uint32_t)(eventid) >>16),OPCODE_PAD,V(eventid & 0xFFFF),
#define ONACOF(eventid) OPCODE_ONACOF,V((uint32_t)(eventid) >>16),OPCODE_PAD,V(eventid & 0xFFFF),
#define LCD(id,msg) PRINT(msg)
#define SCREEN(display,id,msg) PRINT(msg)
#define STEALTH(code...) PRINT(dummy)
#define STEALTH_GLOBAL(code...)
#define LCN(msg) PRINT(msg)
#define MESSAGE(msg) PRINT(msg)
#define MOVETT(id,steps,activity) OPCODE_SERVO,V(id),OPCODE_PAD,V(steps),OPCODE_PAD,V(EXTurntable::activity),OPCODE_PAD,V(0),
#define NEOPIXEL(id,colour) OPCODE_NEOPIXEL,V(id),OPCODE_PAD,V(colour| NEOPIXEL_FLAG_ON),
#define NEOPIXEL_OFF(id,colour) OPCODE_NEOPIXEL,V(id),OPCODE_PAD,V(colour& ^NEOPIXEL_FLAG_ON),
@ -543,6 +580,8 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#endif
#define ONTHROW(turnout_id) OPCODE_ONTHROW,V(turnout_id),
#define ONCHANGE(sensor_id) OPCODE_ONCHANGE,V(sensor_id),
#define ONSENSOR(sensor_id) OPCODE_ONSENSOR,V(sensor_id),
#define ONBUTTON(sensor_id) OPCODE_ONBUTTON,V(sensor_id),
#define PAUSE OPCODE_PAUSE,0,0,
#define PICKUP_STASH(id) OPCODE_PICKUP_STASH,V(id),
#define PIN_TURNOUT(id,pin,description...) OPCODE_PINTURNOUT,V(id),OPCODE_PAD,V(pin),
@ -588,7 +627,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define SET_TRACK(track,mode) OPCODE_SET_TRACK,V(TRACK_MODE_##mode <<8 | TRACK_NUMBER_##track),
#define SET_POWER(track,onoff) OPCODE_SET_POWER,V(TRACK_POWER_##onoff),OPCODE_PAD, V(TRACK_NUMBER_##track),
#define SETLOCO(loco) OPCODE_SETLOCO,V(loco),
#define SETFREQ(loco,freq) OPCODE_SETLOCO,V(loco), OPCODE_SETFREQ,V(freq),
#define SETFREQ(freq) OPCODE_SETFREQ,V(freq),
#define SIGNAL(redpin,amberpin,greenpin)
#define SIGNALH(redpin,amberpin,greenpin)
#define SPEED(speed) OPCODE_SPEED,V(speed),
@ -596,6 +635,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define STASH(id) OPCODE_STASH,V(id),
#define STOP OPCODE_SPEED,V(0),
#define THROW(id) OPCODE_THROW,V(id),
#define TOGGLE_TURNOUT(id) OPCODE_TOGGLE_TURNOUT,V(id),
#ifndef IO_NO_HAL
#define TT_ADDPOSITION(id,position,value,angle,description...) OPCODE_TTADDPOSITION,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(value),OPCODE_PAD,V(angle),
#endif
@ -612,6 +652,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#endif
#define XFOFF(cab,func) OPCODE_XFOFF,V(cab),OPCODE_PAD,V(func),
#define XFON(cab,func) OPCODE_XFON,V(cab),OPCODE_PAD,V(func),
#define XFTOGGLE(cab,func) OPCODE_XFTOGGLE,V(cab),OPCODE_PAD,V(func),
// Build RouteCode
const int StringMacroTracker2=__COUNTER__;

104
EXRAILSensor.cpp Normal file
View File

@ -0,0 +1,104 @@
/*
* © 2024 Chris Harlow
* All rights reserved.
*
* This file is part of CommandStation-EX
*
* 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/>.
*/
/**********************************************************************
EXRAILSensor represents a sensor that should be monitored in order
to call an exrail ONBUTTON or ONCHANGE handler.
These are created at EXRAIL startup and thus need no delete or listing
capability.
The basic logic is similar to that found in the Sensor class
except that on the relevant change an EXRAIL thread is started.
**********************************************************************/
#include "EXRAILSensor.h"
#include "EXRAIL2.h"
void EXRAILSensor::checkAll() {
if (firstSensor == NULL) return; // No sensors to be scanned
if (readingSensor == NULL) {
// Not currently scanning sensor list
unsigned long thisTime = micros();
if (thisTime - lastReadCycle < cycleInterval) return;
// Required time has elapsed since last read cycle started,
// so initiate new scan through the sensor list
readingSensor = firstSensor;
lastReadCycle = thisTime;
}
// Loop until either end of list is encountered or we pause for some reason
byte sensorCount = 0;
while (readingSensor != NULL) {
bool pause=readingSensor->check();
// Move to next sensor in list.
readingSensor = readingSensor->nextSensor;
// Currently process max of 16 sensors per entry.
// Performance measurements taken during development indicate that, with 128 sensors configured
// on 8x 16-pin MCP23017 GPIO expanders with polling (no change notification), all inputs can be read from the devices
// within 1.4ms (400Mhz I2C bus speed), and a full cycle of checking 128 sensors for changes takes under a millisecond.
if (pause || (++sensorCount)>=16) return;
}
}
bool EXRAILSensor::check() {
// check for debounced change in this sensor
inputState = RMFT2::readSensor(pin);
// Check if changed since last time, and process changes.
if (inputState == active) {// no change
latchDelay = minReadCount; // Reset counter
return false; // no change
}
// Change detected ... has it stayed changed for long enough
if (latchDelay > 0) {
latchDelay--;
return false;
}
// change validated, act on it.
active = inputState;
latchDelay = minReadCount; // Reset debounce counter
if (onChange || active) {
new RMFT2(progCounter);
return true; // Don't check any more sensors on this entry
}
return false;
}
EXRAILSensor::EXRAILSensor(VPIN _pin, int _progCounter, bool _onChange) {
// Add to the start of the list
//DIAG(F("ONthing vpin=%d at %d"), _pin, _progCounter);
nextSensor = firstSensor;
firstSensor = this;
pin=_pin;
progCounter=_progCounter;
onChange=_onChange;
IODevice::configureInput(pin, true);
active = IODevice::read(pin);
inputState = active;
latchDelay = minReadCount;
}
EXRAILSensor *EXRAILSensor::firstSensor=NULL;
EXRAILSensor *EXRAILSensor::readingSensor=NULL;
unsigned long EXRAILSensor::lastReadCycle=0;

50
EXRAILSensor.h Normal file
View File

@ -0,0 +1,50 @@
/*
* © 2024 Chris Harlow
* All rights reserved.
*
* This file is part of CommandStation-EX
*
* 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 EXRAILSensor_h
#define EXRAILSensor_h
#include "IODevice.h"
class EXRAILSensor {
static EXRAILSensor * firstSensor;
static EXRAILSensor * readingSensor;
static unsigned long lastReadCycle;
public:
static void checkAll();
EXRAILSensor(VPIN _pin, int _progCounter, bool _onChange);
bool check();
private:
static const unsigned int cycleInterval = 10000; // min time between consecutive reads of each sensor in microsecs.
// should not be less than device scan cycle time.
static const byte minReadCount = 4; // number of additional scans before acting on change
// E.g. 1 means that a change is ignored for one scan and actioned on the next.
// Max value is 63
EXRAILSensor* nextSensor;
VPIN pin;
int progCounter;
bool active;
bool inputState;
bool onChange;
byte latchDelay;
};
#endif

View File

@ -1 +1 @@
#define GITHUB_SHA "devel-202402201404Z"
#define GITHUB_SHA "devel-202408291145Z"

View File

@ -547,7 +547,7 @@ protected:
#include "IO_duinoNodes.h"
#include "IO_EXIOExpander.h"
#include "IO_trainbrains.h"
#include "IO_TCA8418.h"
#include "IO_EncoderThrottle.h"#include "IO_TCA8418.h"
#endif // iodevice_h

View File

@ -51,6 +51,7 @@ static void create(I2CAddress i2cAddress) {
// Start by assuming we will find the clock
// Check if specified I2C address is responding (blocking operation)
// Returns I2C_STATUS_OK (0) if OK, or error code.
I2CManager.begin();
uint8_t _checkforclock = I2CManager.checkAddress(i2cAddress);
DIAG(F("Clock check result - %d"), _checkforclock);
// XXXX change thistosave2 bytes

View File

@ -83,6 +83,7 @@ void EXTurntable::_loop(unsigned long currentMicros) {
// Read returns status as obtained in our loop.
// Return false if our status value is invalid.
int EXTurntable::_read(VPIN vpin) {
(void)vpin; // surpress warning
if (_deviceState == DEVSTATE_FAILED) return 0;
if (_stepperStatus > 1) {
return false;
@ -127,6 +128,8 @@ void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_
vpin, value, activity, duration);
DIAG(F("I2CManager write I2C Address:%d stepsMSB:%d stepsLSB:%d activity:%d"),
_I2CAddress.toString(), stepsMSB, stepsLSB, activity);
#else
(void)duration;
#endif
if (activity < 4) _stepperStatus = 1; // Tell the device driver Turntable-EX is busy
_previousStatus = _stepperStatus;

144
IO_EncoderThrottle.cpp Normal file
View File

@ -0,0 +1,144 @@
/*
* © 2024, Chris Harlow. All rights reserved.
*
* This file is part of EX-CommandStation
*
* 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/>.
*/
/*
* The IO_EncoderThrottle device driver uses a rotary encoder connected to vpins
* to drive a loco.
* Loco id is selected by writeAnalog.
*/
#include "IODevice.h"
#include "DIAG.h"
#include "DCC.h"
const byte _DIR_CW = 0x10; // Clockwise step
const byte _DIR_CCW = 0x20; // Counter-clockwise step
const byte transition_table[5][4]= {
{0,1,3,0}, // 0: 00
{1,1,1,2 | _DIR_CW}, // 1: 00->01
{2,2,0,2}, // 2: 00->01->11
{3,3,3,4 | _DIR_CCW}, // 3: 00->10
{4,0,4,4} // 4: 00->10->11
};
const byte _STATE_MASK = 0x07;
const byte _DIR_MASK = 0x30;
void EncoderThrottle::create(VPIN firstVpin, int dtPin, int clkPin, int clickPin, byte notch) {
if (checkNoOverlap(firstVpin)) new EncoderThrottle(firstVpin, dtPin,clkPin,clickPin,notch);
}
// Constructor
EncoderThrottle::EncoderThrottle(VPIN firstVpin, int dtPin, int clkPin, int clickPin, byte notch){
_firstVpin = firstVpin;
_nPins = 1;
_I2CAddress = 0;
_dtPin=dtPin;
_clkPin=clkPin;
_clickPin=clickPin;
_notch=notch;
_locoid=0;
_stopState=xrSTOP;
_rocoState=0;
_prevpinstate=4; // not 01..11
IODevice::configureInput(dtPin,true);
IODevice::configureInput(clkPin,true);
IODevice::configureInput(clickPin,true);
addDevice(this);
_display();
}
void EncoderThrottle::_loop(unsigned long currentMicros) {
if (_locoid==0) return; // not in use
// Clicking down on the roco, stops the loco and sets the direction as unknown.
if (IODevice::read(_clickPin)) {
if (_stopState==xrSTOP) return; // debounced multiple stops
DCC::setThrottle(_locoid,1,DCC::getThrottleDirection(_locoid));
_stopState=xrSTOP;
DIAG(F("DRIVE %d STOP"),_locoid);
return;
}
// read roco pins and detect state change
byte pinstate = (IODevice::read(_dtPin) << 1) | IODevice::read(_clkPin);
if (pinstate==_prevpinstate) return;
_prevpinstate=pinstate;
_rocoState = transition_table[_rocoState & _STATE_MASK][pinstate];
if ((_rocoState & _DIR_MASK) == 0) return; // no value change
int change=(_rocoState & _DIR_CW)?+1:-1;
// handle roco change -1 or +1 (clockwise)
if (_stopState==xrSTOP) {
// first move after button press sets the direction. (clockwise=fwd)
_stopState=change>0?xrFWD:xrREV;
}
// when going fwd, clockwise increases speed.
// but when reversing, anticlockwise increases speed.
// This is similar to a center-zero pot control but with
// the added safety that you cant panic-spin into the other
// direction.
if (_stopState==xrREV) change=-change;
// manage limits
int oldspeed=DCC::getThrottleSpeed(_locoid);
if (oldspeed==1)oldspeed=0; // break out of estop
int newspeed=change>0 ? (min((oldspeed+_notch),126)) : (max(0,(oldspeed-_notch)));
if (newspeed==1) newspeed=0; // normal decelereated stop.
if (oldspeed!=newspeed) {
DIAG(F("DRIVE %d notch %S %d %S"),_locoid,
change>0?F("UP"):F("DOWN"),_notch,
_stopState==xrFWD?F("FWD"):F("REV"));
DCC::setThrottle(_locoid,newspeed,_stopState==xrFWD);
}
}
// Selocoid as analog value to start drive
// use <z vpin locoid [notch]>
void EncoderThrottle::_writeAnalogue(VPIN vpin, int value, uint8_t param1, uint16_t param2) {
(void) param2;
_locoid=value;
if (param1>0) _notch=param1;
_rocoState=0;
// If loco is moving, we inherit direction from it.
_stopState=xrSTOP;
if (_locoid>0) {
auto speedbyte=DCC::getThrottleSpeedByte(_locoid);
if ((speedbyte & 0x7f) >1) {
// loco is moving
_stopState= (speedbyte & 0x80)?xrFWD:xrREV;
}
}
_display();
}
void EncoderThrottle::_display() {
DIAG(F("DRIVE vpin %d loco %d notch %d"),_firstVpin,_locoid,_notch);
}

53
IO_EncoderThrottle.h Normal file
View File

@ -0,0 +1,53 @@
/*
* © 2024, Chris Harlow. All rights reserved.
*
* This file is part of EX-CommandStation
*
* 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/>.
*/
/*
* The IO_EncoderThrottle device driver uses a rotary encoder connected to vpins
* to drive a loco.
* Loco id is selected by writeAnalog.
*/
#ifndef IO_EncoderThrottle_H
#define IO_EncoderThrottle_H
#include "IODevice.h"
class EncoderThrottle : public IODevice {
public:
static void create(VPIN firstVpin, int dtPin, int clkPin, int clickPin, byte notch=10);
private:
int _dtPin,_clkPin,_clickPin, _locoid, _notch,_prevpinstate;
enum {xrSTOP,xrFWD,xrREV} _stopState;
byte _rocoState;
// Constructor
EncoderThrottle(VPIN firstVpin, int dtPin, int clkPin, int clickPin, byte notch);
void _loop(unsigned long currentMicros) override ;
// Selocoid as analog value to start drive
// use <z vpin locoid [notch]>
void _writeAnalogue(VPIN vpin, int value, uint8_t param1, uint16_t param2) override;
void _display() override ;
};
#endif

View File

@ -1,7 +1,9 @@
/*
* © 2023, Neil McKechnie. All rights reserved.
* © 2024, Paul Antoine
* © 2023, Neil McKechnie
* All rights reserved.
*
* This file is part of DCC++EX API
* 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
@ -112,13 +114,14 @@ protected:
// Fill buffer with spaces
memset(_buffer, ' ', _numCols*_numRows);
_displayDriver->clearNative();
// Add device to list of HAL devices (not necessary but allows
// status to be displayed using <D HAL SHOW> and device to be
// reinitialised using <D HAL RESET>).
IODevice::addDevice(this);
// Moved after addDevice() to ensure I2CManager.begin() has been called fisrt
_displayDriver->clearNative();
// Also add this display to list of display handlers
DisplayInterface::addDisplay(displayNo);

View File

@ -42,9 +42,9 @@
* 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
* HAL(RotaryEncoder, 700, 1, 0x67) // Define single Vpin, no feedback or position sent to rotary encoder software
* HAL(RotaryEncoder, 700, 2, 0x67) // Define two Vpins, feedback only sent to rotary encoder software
* HAL(RotaryEncoder, 700, 3, 0x67) // 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.
*/

View File

@ -26,7 +26,7 @@
Thus "MAIN"_hk generates exactly the same run time vakue
as const int16_t HASH_KEYWORD_MAIN=11339
*/
#ifndef KeywordHAsher_h
#ifndef KeywordHasher_h
#define KeywordHasher_h
#include <Arduino.h>

View File

@ -1,5 +1,6 @@
/*
* © 2022-2023 Paul M Antoine
* © 2022-2024 Paul M Antoine
* © 2024 Herb Morton
* © 2021 Mike S
* © 2021 Fred Decker
* © 2020-2023 Harald Barth
@ -38,6 +39,8 @@ volatile portreg_t shadowPORTC;
volatile portreg_t shadowPORTD;
volatile portreg_t shadowPORTE;
volatile portreg_t shadowPORTF;
volatile portreg_t shadowPORTG;
volatile portreg_t shadowPORTH;
#endif
MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin,
@ -88,6 +91,16 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
fastSignalPin.shadowinout = fastSignalPin.inout;
fastSignalPin.inout = &shadowPORTF;
}
if (HAVE_PORTG(fastSignalPin.inout == &PORTG)) {
DIAG(F("Found PORTG pin %d"),signalPin);
fastSignalPin.shadowinout = fastSignalPin.inout;
fastSignalPin.inout = &shadowPORTG;
}
if (HAVE_PORTH(fastSignalPin.inout == &PORTH)) {
DIAG(F("Found PORTH pin %d"),signalPin);
fastSignalPin.shadowinout = fastSignalPin.inout;
fastSignalPin.inout = &shadowPORTH;
}
signalPin2=signal_pin2;
if (signalPin2!=UNUSED_PIN) {
@ -126,6 +139,16 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
fastSignalPin2.shadowinout = fastSignalPin2.inout;
fastSignalPin2.inout = &shadowPORTF;
}
if (HAVE_PORTG(fastSignalPin2.inout == &PORTG)) {
DIAG(F("Found PORTG pin %d"),signalPin2);
fastSignalPin2.shadowinout = fastSignalPin2.inout;
fastSignalPin2.inout = &shadowPORTG;
}
if (HAVE_PORTH(fastSignalPin2.inout == &PORTH)) {
DIAG(F("Found PORTH pin %d"),signalPin2);
fastSignalPin2.shadowinout = fastSignalPin2.inout;
fastSignalPin2.inout = &shadowPORTH;
}
}
else dualSignal=false;
@ -336,8 +359,6 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/)
if (tSpeed <= 1) brake = 255;
else if (tSpeed >= 127) brake = 0;
else brake = 2 * (128-tSpeed);
if (invertBrake)
brake=255-brake;
{ // new block because of variable f
#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32)
@ -349,12 +370,12 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/)
}
}
#endif
//DIAG(F("Brake pin %d freqency %d"), brakePin, f);
//DIAG(F("Brake pin %d value %d freqency %d"), brakePin, brake, f);
DCCTimer::DCCEXanalogWrite(brakePin, brake, invertBrake);
DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency
DCCTimer::DCCEXanalogWrite(brakePin,brake);
#else // all AVR here
DCCTimer::DCCEXanalogWriteFrequency(brakePin, frequency); // frequency steps
analogWrite(brakePin,brake);
analogWrite(brakePin, invertBrake ? 255-brake : brake);
#endif
}
@ -395,6 +416,18 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/)
setSignal(tDir);
HAVE_PORTF(PORTF=shadowPORTF);
interrupts();
} else if (HAVE_PORTG(fastSignalPin.shadowinout == &PORTG)) {
noInterrupts();
HAVE_PORTG(shadowPORTG=PORTG);
setSignal(tDir);
HAVE_PORTG(PORTG=shadowPORTG);
interrupts();
} else if (HAVE_PORTH(fastSignalPin.shadowinout == &PORTH)) {
noInterrupts();
HAVE_PORTH(shadowPORTH=PORTH);
setSignal(tDir);
HAVE_PORTH(PORTH=shadowPORTH);
interrupts();
} else {
noInterrupts();
setSignal(tDir);
@ -404,26 +437,26 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/)
void MotorDriver::throttleInrush(bool on) {
if (brakePin == UNUSED_PIN)
return;
if ( !(trackMode & (TRACK_MODE_MAIN | TRACK_MODE_PROG | TRACK_MODE_EXT)))
if ( !(trackMode & (TRACK_MODE_MAIN | TRACK_MODE_PROG | TRACK_MODE_EXT | TRACK_MODE_BOOST)))
return;
byte duty = on ? 207 : 0; // duty of 81% at 62500Hz this gives pauses of 3usec
if (invertBrake)
duty = 255-duty;
#if defined(ARDUINO_ARCH_ESP32)
if(on) {
DCCTimer::DCCEXanalogWrite(brakePin,duty);
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max
DCCTimer::DCCEXInrushControlOn(brakePin, duty, invertBrake);
} else {
ledcDetachPin(brakePin);
ledcDetachPin(brakePin); // not DCCTimer::DCCEXledcDetachPin() as we have not
// registered the pin in the pin to channel array
}
#elif defined(ARDUINO_ARCH_STM32)
if(on) {
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max
DCCTimer::DCCEXanalogWrite(brakePin,duty);
DCCTimer::DCCEXanalogWrite(brakePin,duty,invertBrake);
} else {
pinMode(brakePin, OUTPUT);
}
#else // all AVR here
if (invertBrake)
duty = 255-duty;
if(on){
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max
}
@ -606,6 +639,10 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) {
}
throttleInrush(false);
setPower(POWERMODE::ON);
break;
}
if (goodtime > POWER_SAMPLE_ALERT_GOOD/2) {
throttleInrush(false);
}
break;
}

View File

@ -1,5 +1,5 @@
/*
* © 2022-2023 Paul M. Antoine
* © 2022-2024 Paul M. Antoine
* © 2021 Mike S
* © 2021 Fred Decker
* © 2020 Chris Harlow
@ -26,6 +26,7 @@
#include "FSH.h"
#include "IODevice.h"
#include "DCCTimer.h"
#include <wiring_private.h>
// use powers of two so we can do logical and/or on the track modes in if clauses.
// RACK_MODE_DCX is (TRACK_MODE_DC|TRACK_MODE_INV)
@ -34,9 +35,15 @@ template<class T> inline T operator| (T a, T b) { return (T)((int)a | (int)b); }
template<class T> inline T operator& (T a, T b) { return (T)((int)a & (int)b); }
template<class T> inline T operator^ (T a, T b) { return (T)((int)a ^ (int)b); }
enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PROG = 4,
TRACK_MODE_DC = 8, TRACK_MODE_EXT = 16, TRACK_MODE_BOOST = 32,
TRACK_MODE_ALL = 62, // only to operate all tracks
TRACK_MODE_INV = 64, TRACK_MODE_DCX = 72 /*DC + INV*/, TRACK_MODE_AUTOINV = 128};
TRACK_MODE_DC = 8, TRACK_MODE_EXT = 16,
#ifdef ARDUINO_ARCH_ESP32
TRACK_MODE_BOOST = 32,
#else
TRACK_MODE_BOOST = 0,
#endif
TRACK_MODE_ALL = TRACK_MODE_MAIN|TRACK_MODE_PROG|TRACK_MODE_DC|TRACK_MODE_EXT|TRACK_MODE_BOOST,
TRACK_MODE_INV = 64,
TRACK_MODE_DCX = TRACK_MODE_DC|TRACK_MODE_INV, TRACK_MODE_AUTOINV = 128};
#define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH
#define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW
@ -77,6 +84,14 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO
#define PORTF GPIOF->ODR
#define HAVE_PORTF(X) X
#endif
#if defined(GPIOG)
#define PORTG GPIOG->ODR
#define HAVE_PORTG(X) X
#endif
#if defined(GPIOH)
#define PORTH GPIOH->ODR
#define HAVE_PORTH(X) X
#endif
#endif
// if macros not defined as pass-through we define
@ -100,6 +115,12 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO
#ifndef HAVE_PORTF
#define HAVE_PORTF(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
#endif
#ifndef HAVE_PORTG
#define HAVE_PORTG(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
#endif
#ifndef HAVE_PORTH
#define HAVE_PORTH(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
#endif
// Virtualised Motor shield 1-track hardware Interface
@ -139,6 +160,8 @@ extern volatile portreg_t shadowPORTC;
extern volatile portreg_t shadowPORTD;
extern volatile portreg_t shadowPORTE;
extern volatile portreg_t shadowPORTF;
extern volatile portreg_t shadowPORTG;
extern volatile portreg_t shadowPORTH;
enum class POWERMODE : byte { OFF, ON, OVERLOAD, ALERT };
@ -187,13 +210,14 @@ class MotorDriver {
}
};
inline pinpair getSignalPin() { return pinpair(signalPin,signalPin2); };
inline int8_t getBrakePinSigned() { return invertBrake ? -brakePin : brakePin; };
void setDCSignal(byte speedByte, uint8_t frequency=0);
void throttleInrush(bool on);
inline void detachDCSignal() {
#if defined(__arm__)
pinMode(brakePin, OUTPUT);
#elif defined(ARDUINO_ARCH_ESP32)
ledcDetachPin(brakePin);
DCCTimer::DCCEXledcDetachPin(brakePin);
#else
setDCSignal(128);
#endif

View File

@ -1,7 +1,7 @@
/*
* © 2022-2023 Paul M. Antoine
* © 2021 Fred Decker
* © 2020-2023 Harald Barth
* © 2020-2024 Harald Barth
* (c) 2020 Chris Harlow. All rights reserved.
* (c) 2021 Fred Decker. All rights reserved.
* (c) 2020 Harald Barth. All rights reserved.
@ -57,6 +57,10 @@
// of the brake pin on the motor bridge is inverted
// (HIGH == release brake)
// You can have a CS wihout any possibility to do any track signal.
// That's strange but possible.
#define NO_SHIELD F("No shield at all")
// Arduino STANDARD Motor Shield, used on different architectures:
#if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32)
@ -93,6 +97,18 @@
new MotorDriver(25/* 3*/, 19/*12*/, UNUSED_PIN, 13/*9*/, 35/*A2*/, 1.27, 5000, 36 /*A4*/), \
new MotorDriver(23/*11*/, 18/*13*/, UNUSED_PIN, 12/*8*/, 34/*A3*/, 1.27, 5000, 39 /*A5*/)
// EX-CSB1 with integrated motor driver definition
#define EXCSB1 F("EXCSB1"),\
new MotorDriver(25, 0, UNUSED_PIN, -14, 34, 2.23, 5000, 19), \
new MotorDriver(27, 15, UNUSED_PIN, -2, 35, 2.23, 5000, 23)
// EX-CSB1 with EX-8874 stacked on top for 4 outputs
#define EXCSB1_WITH_EX8874 F("EXCSB1_WITH_EX8874"),\
new MotorDriver(25, 0, UNUSED_PIN, -14, 34, 2.23, 5000, 19), \
new MotorDriver(27, 15, UNUSED_PIN, -2, 35, 2.23, 5000, 23), \
new MotorDriver(26, 5, UNUSED_PIN, 13, 36, 1.52, 5000, 18), \
new MotorDriver(16, 4, UNUSED_PIN, 12, 39, 1.52, 5000, 17)
#else
// STANDARD shield on any Arduino Uno or Mega compatible with the original specification.
#define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"), \

View File

@ -0,0 +1,119 @@
// 5.2.49
Which is a more efficient than the AT/AFTER/IF methods
of handling buttons and switches, especially on MIMIC panels.
ONBUTTON(vpin)
handles debounce and starts a task if a button is used to
short a pin to ground.
for example:
ONBUTTON(30) TOGGLE_TURNOUT(30) DONE
ONSENSOR(vpin)
handles debounce and starts a task if the pin changes.
You may want to check the pin state with an IF ...
Note the ONBUTTON and ONSENSOR are not generally useful
for track sensors and running trains, because you dont know which
train triggered the sensor.
// 5.2.47
BLINK(vpin, onMs,offMs)
which will start a vpin blinking until such time as it is SET, RESET or set by a signal operation such as RED, AMBER, GREEN.
BLINK returns immediately, the blinking is autonomous.
This means a signal that always blinks amber could be done like this:
SIGNAL(30,31,32)
ONAMBER(30) BLINK(31,500,500) DONE
The RED or GREEN calls will turn off the amber blink automatically.
Alternatively a signal that has normal AMBER and flashing AMBER could be like this:
#define FLASHAMBER(signal) \
AMBER(signal) \
BLINK(signal+1,500,500)
(Caution: this assumes that the amber pin is redpin+1)
==
FTOGGLE(function)
Toggles the current loco function (see FON and FOFF)
XFTOGGLE(loco,function)
Toggles the function on given loco. (See XFON, XFOFF)
TOGGLE_TURNOUT(id)
Toggles the turnout (see CLOSE, THROW)
STEALTH_GLOBAL(code)
ADVANCED C++ users only.
Inserts code such as static variables and functions that
may be utilised by multiple STEALTH operations.
// 5.2.34 - <A address aspect> Command fopr DCC Extended Accessories.
This command sends an extended accessory packet to the track, Normally used to set
a signal aspect. Aspect numbers are undefined as sdtandards except for 0 which is
always considered a stop.
// - Exrail ASPECT(address,aspect) for above.
The ASPECT command sents an aspect to a DCC accessory using the same logic as
<A aspect address>.
// - EXRAIL DCCX_SIGNAL(Address,redAspect,amberAspect,greenAspect)
This defines a signal (with id same as dcc address) that can be operated
by the RED/AMBER/GREEN commands. In each case the command uses the signal
address to refer to the signal and the aspect chosen depends on the use of the RED
AMBER or GREEN command sent. Other aspects may be sent but will require the
direct use of the ASPECT command.
The IFRED/IFAMBER/IFGREEN and ONRED/ONAMBER/ONGREEN commands contunue to operate
as for any other signal type. It is important to be aware that use of the ASPECT
or <A> commands will correctly set the IF flags and call the ON handlers if ASPECT
is used to set one of the three aspects defined in the DCCX_SIGNAL command.
Direct use of other aspects does not affect the signal flags.
ASPECT and <A> can be used withput defining any signal if tyhe flag management or
ON event handlers are not required.
// 5.2.33 - Exrail CONFIGURE_SERVO(vpin,pos1,pos2,profile)
This macro offsers a more convenient way of performing the HAL call in halSetup.h
In halSetup.h --- IODevice::configureServo(101,300,400,PCA9685::slow);
In myAutomation.h --- CONFIGURE_SERVO(101,300,400,slow)
// 5.2.32 - Railcom Cutout (Initial trial Mega2560 only)
This cutout will only work on a Mega2560 with a single EX8874 motor shield
configured in the normal way with the main track brake pin on pin 9.
<C RAILCOM ON> Turns on the cutout mechanism.
<C RAILCOM OFF> Tirns off the cutout. (This is the default)
<C RAILCOM DEBUG> ONLY to be used by developers used for waveform diagnostics.
(In DEBUG mode the main track idle packets are replaced with reset packets, This
makes it far easier to see the preambles and cutouts on a logic analyser or scope.)
// 5.2.31 - Exrail JMRI_SENSOR(vpin [,count]) creates <S> types.
This Macro causes the creation of JMRI <S> type sensors in a way that is
simpler than repeating lines of <S> commands.
JMRI_SENSOR(100) is equenvelant to <S 100 100 1>
JMRI_SENSOR(100,16) will create <S> type sensors for vpins 100-115.
// 5.2.26 - Silently ignore overridden HAL defaults
// - include HAL_IGNORE_DEFAULTS macro in EXRAIL
The HAL_IGNORE_DEFAULTS command, anywhere in myAutomation.h will
prevent the startup code from trying the default I2C sensors/servos.
// 5.2.24 - Exrail macro asserts to catch
// : duplicate/missing automation/route/sequence/call ids
// : latches and reserves out of range
// : speeds out of range
Causes compiler time messages for EXRAIL issues that would normally
only be discovered by things going wrong at run time.
// 5.2.13 - EXRAIL STEALTH
Permits a certain level of C++ code to be embedded as a single step in
an exrail sequence. Serious engineers only.
// 5.2.9 - EXRAIL STASH feature
// - Added ROUTE_DISABLED macro in EXRAIL

View File

@ -68,7 +68,11 @@ void SerialManager::init() {
new SerialManager(&Serial3);
#endif
#ifdef SERIAL2_COMMANDS
#ifdef ARDUINO_ARCH_ESP32
Serial2.begin(115200, SERIAL_8N1, 16, 17); // GPIO 16 RXD2; GPIO 17 TXD2 on ESP32
#else // not ESP32
Serial2.begin(115200);
#endif // ESP32
new SerialManager(&Serial2);
#endif
#ifdef SERIAL1_COMMANDS
@ -88,8 +92,10 @@ void SerialManager::init() {
}
#endif
#ifdef SABERTOOTH
#ifdef ARDUINO_ARCH_ESP32
Serial2.begin(9600, SERIAL_8N1, 16, 17); // GPIO 16 RXD2; GPIO 17 TXD2 on ESP32
#endif
#endif
}
void SerialManager::broadcast(char * stringBuffer) {

View File

@ -139,6 +139,7 @@ void StringFormatter::send2(Print * stream,const FSH* format, va_list args) {
case 'd': printPadded(stream,va_arg(args, int), formatWidth, formatLeft); break;
case 'u': printPadded(stream,va_arg(args, unsigned int), formatWidth, formatLeft); break;
case 'l': printPadded(stream,va_arg(args, long), formatWidth, formatLeft); break;
case 'L': stream->print(va_arg(args, unsigned long), DEC); break;
case 'b': stream->print(va_arg(args, int), BIN); break;
case 'o': stream->print(va_arg(args, int), OCT); break;
case 'x': stream->print((unsigned int)va_arg(args, unsigned int), HEX); break;

View File

@ -1,6 +1,8 @@
/*
* © 2022 Chris Harlow
* © 2022,2023 Harald Barth
* © 2022-2024 Harald Barth
* © 2023-2024 Paul M. Antoine
* © 2024 Herb Morton
* © 2023 Colin Murdoch
* All rights reserved.
*
@ -35,13 +37,13 @@
#define APPLY_BY_MODE(findmode,function) \
FOR_EACH_TRACK(t) \
if (track[t]->getMode()==findmode) \
if (track[t]->getMode() & findmode) \
track[t]->function;
MotorDriver * TrackManager::track[MAX_TRACKS];
int16_t TrackManager::trackDCAddr[MAX_TRACKS];
MotorDriver * TrackManager::track[MAX_TRACKS] = { NULL };
int16_t TrackManager::trackDCAddr[MAX_TRACKS] = { 0 };
byte TrackManager::lastTrack=0;
int8_t TrackManager::lastTrack=-1;
bool TrackManager::progTrackSyncMain=false;
bool TrackManager::progTrackBoosted=false;
int16_t TrackManager::joinRelay=UNUSED_PIN;
@ -149,6 +151,8 @@ void TrackManager::setDCCSignal( bool on) {
HAVE_PORTD(shadowPORTD=PORTD);
HAVE_PORTE(shadowPORTE=PORTE);
HAVE_PORTF(shadowPORTF=PORTF);
HAVE_PORTG(shadowPORTF=PORTG);
HAVE_PORTH(shadowPORTF=PORTH);
APPLY_BY_MODE(TRACK_MODE_MAIN,setSignal(on));
HAVE_PORTA(PORTA=shadowPORTA);
HAVE_PORTB(PORTB=shadowPORTB);
@ -156,6 +160,8 @@ void TrackManager::setDCCSignal( bool on) {
HAVE_PORTD(PORTD=shadowPORTD);
HAVE_PORTE(PORTE=shadowPORTE);
HAVE_PORTF(PORTF=shadowPORTF);
HAVE_PORTG(shadowPORTF=PORTG);
HAVE_PORTH(shadowPORTF=PORTH);
}
// setPROGSignal(), called from interrupt context
@ -167,6 +173,8 @@ void TrackManager::setPROGSignal( bool on) {
HAVE_PORTD(shadowPORTD=PORTD);
HAVE_PORTE(shadowPORTE=PORTE);
HAVE_PORTF(shadowPORTF=PORTF);
HAVE_PORTG(shadowPORTF=PORTG);
HAVE_PORTH(shadowPORTF=PORTH);
APPLY_BY_MODE(TRACK_MODE_PROG,setSignal(on));
HAVE_PORTA(PORTA=shadowPORTA);
HAVE_PORTB(PORTB=shadowPORTB);
@ -174,6 +182,8 @@ void TrackManager::setPROGSignal( bool on) {
HAVE_PORTD(PORTD=shadowPORTD);
HAVE_PORTE(PORTE=shadowPORTE);
HAVE_PORTF(PORTF=shadowPORTF);
HAVE_PORTG(shadowPORTF=PORTG);
HAVE_PORTH(shadowPORTF=PORTH);
}
// setDCSignal(), called from normal context
@ -219,7 +229,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
if (mode & TRACK_MODE_BOOST) {
//DIAG(F("Track=%c mode boost pin %d"),trackToSet+'A', p.pin);
pinMode(BOOSTER_INPUT, INPUT);
gpio_matrix_in(26, SIG_IN_FUNC228_IDX, false); //pads 224 to 228 available as loopback
gpio_matrix_in(BOOSTER_INPUT, SIG_IN_FUNC228_IDX, false); //pads 224 to 228 available as loopback
gpio_matrix_out(p.pin, SIG_IN_FUNC228_IDX, false, false);
if (p.invpin != UNUSED_PIN) {
gpio_matrix_out(p.invpin, SIG_IN_FUNC228_IDX, true /*inverted*/, false);
@ -251,18 +261,47 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
} else {
track[trackToSet]->makeProgTrack(false); // only the prog track knows it's type
}
track[trackToSet]->setMode(mode);
trackDCAddr[trackToSet]=dcAddr;
// When a track is switched, we must clear any side effects of its previous
// state, otherwise trains run away or just dont move.
// This can be done BEFORE the PWM-Timer evaluation (methinks)
if (!(mode & TRACK_MODE_DC)) {
if (mode & TRACK_MODE_DC) {
if (trackDCAddr[trackToSet] != dcAddr) {
// new or changed DC Addr, run the new setup
if (trackDCAddr[trackToSet] != 0) {
// if we change dcAddr and not only
// change from another mode,
// first detach old DC signal
track[trackToSet]->detachDCSignal();
}
#ifdef ARDUINO_ARCH_ESP32
int trackfound = -1;
FOR_EACH_TRACK(t) {
//DIAG(F("Checking track %c mode %x dcAddr %d"), 'A'+t, track[t]->getMode(), trackDCAddr[t]);
if (t != trackToSet // not our track
&& (track[t]->getMode() & TRACK_MODE_DC) // right mode
&& trackDCAddr[t] == dcAddr) { // right addr
//DIAG(F("Found track %c"), 'A'+t);
trackfound = t;
break;
}
}
if (trackfound > -1) {
DCCTimer::DCCEXanalogCopyChannel(track[trackfound]->getBrakePinSigned(),
track[trackToSet]->getBrakePinSigned());
}
#endif
}
// set future DC Addr;
trackDCAddr[trackToSet]=dcAddr;
} else {
// DCC tracks need to have set the PWM to zero or they will not work.
track[trackToSet]->detachDCSignal();
track[trackToSet]->setBrake(false);
trackDCAddr[trackToSet]=0; // clear that an addr is set for DC as this is not a DC track
}
track[trackToSet]->setMode(mode);
// BOOST:
// Leave it as is
@ -362,13 +401,14 @@ bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[])
if (params==2 && p[1]=="EXT"_hk) // <= id EXT>
return setTrackMode(p[0],TRACK_MODE_EXT);
#ifdef BOOSTER_INPUT
if (params==2 && p[1]=="BOOST"_hk) // <= id BOOST>
if (TRACK_MODE_BOOST != 0 && // compile time optimization
params==2 && p[1]=="BOOST"_hk) // <= id BOOST>
return setTrackMode(p[0],TRACK_MODE_BOOST);
#endif
if (params==2 && p[1]=="AUTO"_hk) // <= id AUTO>
return setTrackMode(p[0], track[p[0]]->getMode() | TRACK_MODE_AUTOINV);
if (params==2 && p[1]=="INV"_hk) // <= id AUTO>
if (params==2 && p[1]=="INV"_hk) // <= id INV>
return setTrackMode(p[0], track[p[0]]->getMode() | TRACK_MODE_INV);
if (params==3 && p[1]=="DC"_hk && p[2]>0) // <= id DC cab>
@ -401,11 +441,11 @@ const FSH* TrackManager::getModeName(TRACK_MODE tm) {
modename=F("EXT");
else if(tm & TRACK_MODE_BOOST) {
if(tm & TRACK_MODE_AUTOINV)
modename=F("B A");
modename=F("BOOST A");
else if (tm & TRACK_MODE_INV)
modename=F("B I");
modename=F("BOOST I");
else
modename=F("B");
modename=F("BOOST");
}
else if (tm & TRACK_MODE_DC) {
if (tm & TRACK_MODE_INV)
@ -497,7 +537,11 @@ void TrackManager::setTrackPower(TRACK_MODE trackmodeToMatch, POWERMODE powermod
// Set track power for this track, inependent of mode
void TrackManager::setTrackPower(POWERMODE powermode, byte t) {
MotorDriver *driver=track[t];
MotorDriver *driver=track[t];
if (driver == NULL) { // track is not defined at all
DIAG(F("Error: Track %c does not exist"), t+'A');
return;
}
TRACK_MODE trackmode = driver->getMode();
POWERMODE oldpower = driver->getPower();
if (trackmode & TRACK_MODE_NONE) {
@ -597,23 +641,25 @@ void TrackManager::setJoinRelayPin(byte joinRelayPin) {
void TrackManager::setJoin(bool joined) {
#ifdef ARDUINO_ARCH_ESP32
if (joined) {
if (joined) { // if we go into joined mode (PROG acts as MAIN)
FOR_EACH_TRACK(t) {
if (track[t]->getMode() & TRACK_MODE_PROG) {
tempProgTrack = t;
if (track[t]->getMode() & TRACK_MODE_PROG) { // find PROG track
tempProgTrack = t; // remember PROG track
setTrackMode(t, TRACK_MODE_MAIN);
break;
track[t]->setPower(POWERMODE::ON); // if joined, always on
break; // there is only one prog track, done
}
}
} else {
if (tempProgTrack != MAX_TRACKS+1) {
// as setTrackMode with TRACK_MODE_PROG defaults to
// power off, we will take the current power state
// of our track and then preserve that state.
POWERMODE tPTmode = track[tempProgTrack]->getPower(); //get current power status of this track
setTrackMode(tempProgTrack, TRACK_MODE_PROG);
track[tempProgTrack]->setPower(tPTmode); //set track status as it was before
// setTrackMode defaults to power off, so we
// need to preserve that state.
POWERMODE tPTmode = track[tempProgTrack]->getPower(); // get current power status of this track
setTrackMode(tempProgTrack, TRACK_MODE_PROG); // set track mode back to prog
track[tempProgTrack]->setPower(tPTmode); // set power status as it was before
tempProgTrack = MAX_TRACKS+1;
} else {
DIAG(F("Unjoin but no remembered prog track"));
}
}
#endif

View File

@ -1,6 +1,6 @@
/*
* © 2022 Chris Harlow
* © 2022 Harald Barth
* © 2022-2024 Harald Barth
* © 2023 Colin Murdoch
*
* All rights reserved.
@ -46,7 +46,7 @@ const byte TRACK_POWER_1=1, TRACK_POWER_ON=1;
class TrackManager {
public:
static void Setup(const FSH * shieldName,
MotorDriver * track0,
MotorDriver * track0=NULL,
MotorDriver * track1=NULL,
MotorDriver * track2=NULL,
MotorDriver * track3=NULL,
@ -108,7 +108,7 @@ class TrackManager {
private:
static void addTrack(byte t, MotorDriver* driver);
static byte lastTrack;
static int8_t lastTrack;
static byte nextCycleTrack;
static void applyDCSpeed(byte t);

View File

@ -123,7 +123,6 @@
return true;
}
#define DIAG_IO
// Static setClosed function is invoked from close(), throw() etc. to perform the
// common parts of the turnout operation. Code which is specific to a turnout
// type should be placed in the virtual function setClosedInternal(bool) which is

View File

@ -571,7 +571,7 @@ void WiThrottle::sendRoutes(Print* stream) {
void WiThrottle::sendFunctions(Print* stream, byte loco) {
int16_t locoid=myLocos[loco].cab;
int fkeys=29;
int fkeys=32; // upper limit (send functions 0 to 31)
myLocos[loco].functionToggles=1<<2; // F2 (HORN) is a non-toggle
#ifdef EXRAIL_ACTIVE

View File

@ -147,6 +147,12 @@ bool WifiESP::setup(const char *SSid,
// enableCoreWDT(1);
// disableCoreWDT(0);
#ifdef WIFI_LED
// Turn off Wifi LED
pinMode(WIFI_LED, OUTPUT);
digitalWrite(WIFI_LED, 0);
#endif
// clean start
WiFi.mode(WIFI_STA);
WiFi.disconnect(true);
@ -247,6 +253,13 @@ bool WifiESP::setup(const char *SSid,
// no idea to go on
return false;
}
#ifdef WIFI_LED
else{
// Turn on Wifi connected LED
digitalWrite(WIFI_LED, 1);
}
#endif
// Now Wifi is up, register the mDNS service
if(!MDNS.begin(hostname)) {

View File

@ -1,4 +1,5 @@
/*
* © 2022-2024 Paul M. Antoine
* © 2021 Fred Decker
* © 2020-2022 Harald Barth
* © 2020-2022 Chris Harlow
@ -70,7 +71,7 @@ Stream * WifiInterface::wifiStream;
#define SERIAL3 Serial5
#elif defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) \
|| defined(ARDUINO_NUCLEO_F446ZE) || defined(ARDUINO_NUCLEO_F412ZG) \
|| defined(ARDUINO_NUCLEO_F439ZI)
|| defined(ARDUINO_NUCLEO_F439ZI) || defined(ARDUINO_NUCLEO_F4X9ZI)
#define NUM_SERIAL 2
#define SERIAL1 Serial6
#else

View File

@ -211,6 +211,19 @@ The configuration file for DCC-EX Command Station
// #define DISABLE_VDPY
// #define ENABLE_VDPY
/////////////////////////////////////////////////////////////////////////////////////
// DISABLE / ENABLE DIAG
//
// To diagose different errors, you can turn on differnet messages. This costs
// program memory which we do not have enough on the Uno and Nano, so it is
// by default DISABLED on those. If you think you can fit it (for example
// having disabled some of the features above) you can enable it with
// ENABLE_DIAG. You can even disable it on all other CPUs with
// DISABLE_DIAG
//
// #define DISABLE_DIAG
// #define ENABLE_DIAG
/////////////////////////////////////////////////////////////////////////////////////
// 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
@ -294,11 +307,21 @@ The configuration file for DCC-EX Command Station
//
//#define SERIAL_BT_COMMANDS
// BOOSTER PIN INPUT ON ESP32
// BOOSTER PIN INPUT ON ESP32 CS
// On ESP32 you have the possibility to define a pin as booster input
// Arduio pin D2 is GPIO 26 on ESPDuino32
//
// Arduino pin D2 is GPIO 26 is Booster Input on ESPDuino32
//#define BOOSTER_INPUT 26
//
// GPIO 32 is Booster Input on EX-CSB1
//#define BOOSTER_INPUT 32
// ESP32 LED Wifi Indicator
// GPIO 2 on ESPduino32
//#define WIFI_LED 2
//
// GPIO 33 on EX-CSB1
//#define WIFI_LED 33
// SABERTOOTH
//

View File

@ -220,9 +220,15 @@
//
#if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO)
#define IO_NO_HAL // HAL too big whatever you disable otherwise
#ifndef ENABLE_VDPY
#define DISABLE_VDPY
#endif
#ifndef ENABLE_DIAG
#define DISABLE_DIAG
#endif
#endif
#if __has_include ( "myAutomation.h")

View File

@ -311,12 +311,13 @@ void halSetup() {
//=======================================================================
// The parameters are:
// firstVpin = First available Vpin to allocate
// numPins= Number of Vpins to allocate, can be either 1 or 2
// i2cAddress = Available I2C address (default 0x70)
// numPins= Number of Vpins to allocate, can be either 1 to 3
// i2cAddress = Available I2C address (default 0x67)
//RotaryEncoder::create(firstVpin, numPins, i2cAddress);
//RotaryEncoder::create(700, 1, 0x70);
//RotaryEncoder::create(701, 2, 0x71);
//RotaryEncoder::create(700, 1, 0x67);
//RotaryEncoder::create(700, 2, 0x67);
//RotaryEncoder::create(700, 3, 0x67);
//=======================================================================
// The following directive defines an EX-FastClock instance.

View File

@ -164,7 +164,11 @@ monitor_echo = yes
build_flags = -mcall-prologues
[env:ESP32]
platform = espressif32
; Lock version to 6.7.0 as that is
; Arduino v2.0.16 (based on IDF v4.4.7)
; which is the latest version based
; on IDF v4. We can not use IDF v5.
platform = espressif32 @ 6.7.0
board = esp32dev
framework = arduino
lib_deps = ${env.lib_deps}

View File

@ -3,8 +3,67 @@
#include "StringFormatter.h"
#define VERSION "5.2.36i2c"
// 5.2.36i2c - Add various I2C drivers, including TCA8418 and Adafruit NeoPixel Driver initially
#define VERSION "5.2.75i2c"
// 5.2.75i2c - Add various I2C drivers, including TCA8418 and Adafruit NeoPixel Driver initially
// 5.2.75 - Bugfix: Serial lines 4 to 6 OK
// 5.2.74 - Bugfix: ESP32 turn on the joined prog (as main) again after a prog operation
// 5.2.73 - Bugfix: STM32 further fixes to shadowPORT entries in TrackManager.cpp for PORTG and PORTH
// 5.2.72 - Bugfix: added shadowPORT entries in TrackManager.cpp for PORTG and PORTH on STM32, fixed typo in MotorDriver.cpp
// 5.2.71 - Broadcasts of loco forgets.
// 5.2.70 - IO_RocoDriver renamed to IO_EncoderThrottle.
// - and included in IODEvice.h (circular dependency removed)
// 5.2.69 - IO_RocoDriver. Direct drive train with rotary encoder hw.
// 5.2.68 - Revert function map to signed (from 5.2.66) to avoid
// incompatibilities with ED etc for F31 frequency flag.
// 5.2.67 - EXRAIL AFTER optional debounce time variable (default 500mS)
// - AFTER(42) == AFTER(42,500) sets time sensor must
// - be continuously off.
// 5.2.66 - <F cab DCFREQ 0..3>
// - EXRAIL SETFREQ drop loco param (breaking since 5.2.28)
// 5.2.65 - Speedup Exrail SETFREQ
// 5.2.64 - Bugfix: <0 PROG> updated to undo JOIN
// 5.2.63 - Implement WIFI_LED for ESP32, ESPduino32 and EX-CSB1, that is turned on when STA mode connects or AP mode is up
// - Add BOOSTER_INPUT definitions for ESPduino32 and EX-CSB1 to config.example.h
// - Add WIFI_LED definitions for ESPduino32 and EX-CSB1 to config.example.h
// 5.2.62 - Allow acks way longer than standard
// 5.2.61 - Merg CBUS ACON/ACOF/ONACON/ONACOF Adapter interface.
// - LCC Adapter interface throttled startup,
// (Breaking change with Adapter base code)
// 5.2.60 - Bugfix: Opcode AFTEROVERLOAD does not have an argument that is a pin and needs to be initialized
// - Remove inrush throttle after half good time so that we go to mode overload if problem persists
// 5.2.59 - STM32 bugfix correct Serial1 definition for Nucleo-F401RE
// - STM32 add support for ARDUINO_NUCLEO_F4X9ZI type to span F429/F439 in upcoming STM32duino release v2.8 as a result of our PR
// 5.2.58 - EXRAIL ALIAS allows named pins
// 5.2.57 - Bugfix autoreverse: Apply mode by binart bit match and not by equality
// 5.2.56 - Bugfix and refactor for EXRAIL getSignalSlot
// 5.2.55 - Move EXRAIL isSignal() to public to allow use in STEALTH call
// 5.2.54 - Bugfix for EXRAIL signal handling for active high
// 5.2.53 - Bugfix for EX-Fastclock, call I2CManager.begin() before checking I2C address
// 5.2.52 - Bugfix for ADCee() to handle ADC2 and ADC3 channel inputs on F446ZE and others
// - Add support for ports G and H on STM32 for ADCee() and MotorDriver pins/shadow regs
// 5.2.51 - Bugfix for SIGNAL: Distinguish between sighandle and sigid
// 5.2.50 - EXRAIL ONBUTTON/ONSENSOR observe LATCH
// 5.2.49 - EXRAIL additions:
// ONBUTTON, ONSENSOR
// 5.2.48 - Bugfix: HALDisplay was generating I2C traffic prior to I2C being initialised
// 5.2.47 - EXRAIL additions:
// STEALTH_GLOBAL
// BLINK
// TOGGLE_TURNOUT
// FTOGGLE, XFTOGGLE
// Reduced code-developmenmt DIAG noise
// 5.2.46 - Support for extended consist CV20 in <R> and <W id>
// - New cmd <W CONSIST id [REVERSE]> to handle long/short consist ids
// 5.2.45 - ESP32 Trackmanager reset cab number to 0 when track is not DC
// ESP32 fix PWM LEDC inverted pin mode
// ESP32 rewrite PWM LEDC to use pin mux
// 5.2.42 - ESP32 Bugfix: Uninitialized stack variable
// 5.2.41 - Update rotary encoder default address to 0x67
// 5.2.40 - Allow no shield
// 5.2.39 - Functions for DC frequency: Use func up to F31
// 5.2.38 - Exrail MESSAGE("text") to send a user message to all
// connected throttles (uses <m "text"> and withrottle Hmtext.
// 5.2.37 - Bugfix ESP32: Use BOOSTER_INPUT define
// 5.2.36 - Variable frequency for DC mode
// 5.2.35 - Bugfix: Make DCC Extended Accessories follow RCN-213
// 5.2.34 - <A address aspect> Command fopr DCC Extended Accessories