mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2025-07-29 02:13:45 +02:00
Compare commits
68 Commits
v5.2.45-De
...
v5.2.77-De
Author | SHA1 | Date | |
---|---|---|---|
|
fe2f705fa9 | ||
|
2606d73d93 | ||
|
4ab77c21ed | ||
|
b53384ab51 | ||
|
b026417efb | ||
|
7ffbd9d0e8 | ||
|
6fa5511670 | ||
|
c07ac38ab1 | ||
|
7395aa4af8 | ||
|
2397b773d7 | ||
|
9a08f2df63 | ||
|
ed853eef1d | ||
|
05e77c924e | ||
|
c5c5609fc6 | ||
|
9c263062e4 | ||
|
f39fd89fbd | ||
|
4e57a80265 | ||
|
27dc8059d7 | ||
|
dc2eae499f | ||
|
c518dcdc0b | ||
|
e6047f6693 | ||
|
96c4757cc6 | ||
|
60e564df51 | ||
|
a8b4e39733 | ||
|
d705626f4a | ||
|
c97284c15f | ||
|
df1f365c1e | ||
|
023c004842 | ||
|
2481f1c5d6 | ||
|
7dadecb5df | ||
|
6ef312b510 | ||
|
97f9fb4813 | ||
|
3d6c935308 | ||
|
fba9a30813 | ||
|
5f65fd5944 | ||
|
a26610bc7f | ||
|
264a53dacf | ||
|
0c96d4ffc2 | ||
|
843fa42692 | ||
|
b17dc5a0dd | ||
|
449a5f1670 | ||
|
06b8995861 | ||
|
2172d2e175 | ||
|
86291cbec4 | ||
|
66791b19f5 | ||
|
6689a1d35f | ||
|
91818ed80c | ||
|
86310aea4f | ||
|
a610e83f6e | ||
|
1449dc7bac | ||
|
bd11cfbf8b | ||
|
16214fad66 | ||
|
76ad3ee48d | ||
|
742b100f65 | ||
|
83d4930124 | ||
|
b4e7982099 | ||
|
3af2f67792 | ||
|
c382bd33bc | ||
|
ebe8f62cf0 | ||
|
7dafe0383d | ||
|
4aa97e1731 | ||
|
91e60b3716 | ||
|
8a5a832b1d | ||
|
5ea6feb11a | ||
|
263c3d01e3 | ||
|
182479c07b | ||
|
3317b4666e | ||
|
f41f61dd5f |
@@ -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){
|
||||
@@ -248,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++)
|
||||
|
@@ -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);
|
||||
|
53
DCC.cpp
53
DCC.cpp
@@ -271,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
|
||||
@@ -615,6 +629,19 @@ 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,20
|
||||
@@ -689,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
3
DCC.h
@@ -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
|
||||
|
12
DCCACK.cpp
12
DCCACK.cpp
@@ -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.
|
||||
|
10
DCCACK.h
10
DCCACK.h
@@ -79,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;
|
||||
}
|
||||
|
||||
@@ -126,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;
|
||||
|
@@ -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
|
||||
@@ -70,8 +70,8 @@ Once a new OPCODE is decided upon, update this list.
|
||||
L, Reserved for LCC interface (implemented in EXRAIL)
|
||||
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
|
||||
*/
|
||||
|
||||
@@ -458,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
|
||||
@@ -560,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);
|
||||
}
|
||||
@@ -638,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;
|
||||
@@ -797,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
|
||||
|
||||
@@ -1069,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>
|
||||
@@ -1347,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();
|
||||
}
|
||||
|
@@ -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;
|
||||
|
@@ -1,5 +1,5 @@
|
||||
/*
|
||||
* © 2022-2023 Paul M. Antoine
|
||||
* © 2022-2024 Paul M. Antoine
|
||||
* © 2021 Mike S
|
||||
* © 2021-2023 Harald Barth
|
||||
* © 2021 Fred Decker
|
||||
@@ -135,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;
|
||||
|
@@ -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
|
||||
|
||||
}
|
||||
|
||||
|
@@ -76,8 +76,13 @@ 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>
|
||||
@@ -292,7 +297,12 @@ void DCCTimer::DCCEXInrushControlOn(uint8_t pin, int duty, bool inverted) {
|
||||
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() {
|
||||
|
@@ -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
|
||||
@@ -363,9 +377,9 @@ void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value, bool invert) {
|
||||
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()
|
||||
{
|
||||
@@ -383,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)
|
||||
{
|
||||
@@ -432,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
|
||||
|
239
EXRAIL2.cpp
239
EXRAIL2.cpp
@@ -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) {
|
||||
@@ -468,10 +478,15 @@ bool RMFT2::skipIfBlock() {
|
||||
|
||||
|
||||
/* static */ void RMFT2::readLocoCallback(int16_t cv) {
|
||||
if (cv <= 0) {
|
||||
DIAG(F("CV read error"));
|
||||
progtrackLocoId = -1;
|
||||
return;
|
||||
}
|
||||
if (cv & LONG_ADDR_MARKER) { // maker bit indicates long addr
|
||||
progtrackLocoId = cv ^ LONG_ADDR_MARKER; // remove marker bit to get real long addr
|
||||
if (progtrackLocoId <= HIGHEST_SHORT_ADDR ) { // out of range for long addr
|
||||
DIAG(F("Long addr %d <= %d unsupported\n"), progtrackLocoId, HIGHEST_SHORT_ADDR);
|
||||
DIAG(F("Long addr %d <= %d unsupported"), progtrackLocoId, HIGHEST_SHORT_ADDR);
|
||||
progtrackLocoId = -1;
|
||||
}
|
||||
} else {
|
||||
@@ -480,6 +495,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 +508,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 +545,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 +598,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 +664,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 +723,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 +833,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 +852,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
|
||||
@@ -900,11 +926,10 @@ void RMFT2::loop2() {
|
||||
delayMe(100);
|
||||
return; // still waiting for callback
|
||||
}
|
||||
if (progtrackLocoId<0) {
|
||||
kill(F("No Loco Found"),progtrackLocoId);
|
||||
return; // still waiting for callback
|
||||
}
|
||||
|
||||
// At failed read will result in loco == -1
|
||||
// which is intended so it can be checked
|
||||
// from within EXRAIL
|
||||
loco=progtrackLocoId;
|
||||
speedo=0;
|
||||
forward=true;
|
||||
@@ -947,6 +972,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)
|
||||
@@ -1025,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
|
||||
@@ -1035,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:
|
||||
@@ -1043,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
|
||||
@@ -1088,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.
|
||||
@@ -1121,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;
|
||||
}
|
||||
@@ -1150,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;
|
||||
}
|
||||
|
||||
@@ -1161,22 +1205,25 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
|
||||
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);
|
||||
}
|
||||
}
|
||||
@@ -1198,8 +1245,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)) {
|
||||
@@ -1248,7 +1296,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);
|
||||
@@ -1258,12 +1306,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;
|
||||
|
29
EXRAIL2.h
29
EXRAIL2.h
@@ -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,11 +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,
|
||||
// OPcodes below this point are skip-nesting IF operations
|
||||
// placed here so that they may be skipped as a group
|
||||
// see skipIfBlock()
|
||||
@@ -98,12 +102,22 @@ enum thrunger: byte {
|
||||
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
|
||||
@@ -174,7 +188,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[]) ;
|
||||
@@ -183,7 +199,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
|
||||
@@ -192,11 +207,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();
|
||||
@@ -244,10 +259,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;
|
||||
|
@@ -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
|
||||
@@ -97,6 +99,10 @@
|
||||
#undef LCCX
|
||||
#undef LCN
|
||||
#undef MOVETT
|
||||
#undef ACON
|
||||
#undef ACOF
|
||||
#undef ONACON
|
||||
#undef ONACOF
|
||||
#undef MESSAGE
|
||||
#undef ONACTIVATE
|
||||
#undef ONACTIVATEL
|
||||
@@ -112,6 +118,8 @@
|
||||
#undef ONGREEN
|
||||
#undef ONRED
|
||||
#undef ONROTATE
|
||||
#undef ONBUTTON
|
||||
#undef ONSENSOR
|
||||
#undef ONTHROW
|
||||
#undef ONCHANGE
|
||||
#undef PARSE
|
||||
@@ -164,8 +172,10 @@
|
||||
#undef START
|
||||
#undef STASH
|
||||
#undef STEALTH
|
||||
#undef STEALTH_GLOBAL
|
||||
#undef STOP
|
||||
#undef THROW
|
||||
#undef TOGGLE_TURNOUT
|
||||
#undef TT_ADDPOSITION
|
||||
#undef TURNOUT
|
||||
#undef TURNOUTL
|
||||
@@ -180,11 +190,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)
|
||||
@@ -196,6 +207,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)
|
||||
@@ -225,6 +237,7 @@
|
||||
#define FON(func)
|
||||
#define FORGET
|
||||
#define FREE(blockid)
|
||||
#define FTOGGLE(func)
|
||||
#define FWD(speed)
|
||||
#define GREEN(signal_id)
|
||||
#define HAL(haltype,params...)
|
||||
@@ -256,6 +269,10 @@
|
||||
#define LCN(msg)
|
||||
#define MESSAGE(msg)
|
||||
#define MOVETT(id,steps,activity)
|
||||
#define ACON(eventid)
|
||||
#define ACOF(eventid)
|
||||
#define ONACON(eventid)
|
||||
#define ONACOF(eventid)
|
||||
#define ONACTIVATE(addr,subaddr)
|
||||
#define ONACTIVATEL(linear)
|
||||
#define ONAMBER(signal_id)
|
||||
@@ -272,6 +289,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)
|
||||
@@ -315,15 +334,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...)
|
||||
@@ -338,4 +359,6 @@
|
||||
#define WITHROTTLE(msg)
|
||||
#define XFOFF(cab,func)
|
||||
#define XFON(cab,func)
|
||||
#define XFTOGGLE(cab,func)
|
||||
|
||||
#endif
|
||||
|
@@ -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);
|
||||
}
|
||||
}
|
||||
|
||||
|
@@ -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.
|
||||
@@ -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"
|
||||
@@ -183,6 +189,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
|
||||
@@ -202,6 +216,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"
|
||||
@@ -417,10 +437,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"
|
||||
@@ -439,7 +463,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),
|
||||
@@ -451,6 +475,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),
|
||||
@@ -484,6 +509,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...)
|
||||
@@ -515,9 +541,14 @@ 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),
|
||||
@@ -542,6 +573,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),
|
||||
@@ -587,7 +620,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),
|
||||
@@ -595,6 +628,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
|
||||
@@ -611,6 +645,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
104
EXRAILSensor.cpp
Normal 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
50
EXRAILSensor.h
Normal 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
|
@@ -1 +1 @@
|
||||
#define GITHUB_SHA "devel-202404061747Z"
|
||||
#define GITHUB_SHA "devel-202409121220Z"
|
||||
|
@@ -547,6 +547,6 @@ protected:
|
||||
#include "IO_duinoNodes.h"
|
||||
#include "IO_EXIOExpander.h"
|
||||
#include "IO_trainbrains.h"
|
||||
|
||||
#include "IO_EncoderThrottle.h"
|
||||
|
||||
#endif // iodevice_h
|
||||
|
@@ -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
|
||||
|
144
IO_EncoderThrottle.cpp
Normal file
144
IO_EncoderThrottle.cpp
Normal 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
53
IO_EncoderThrottle.h
Normal 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
|
@@ -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);
|
||||
|
||||
|
@@ -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>
|
||||
|
@@ -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;
|
||||
|
||||
@@ -393,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);
|
||||
@@ -604,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;
|
||||
}
|
||||
|
@@ -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)
|
||||
@@ -83,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
|
||||
@@ -106,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
|
||||
|
||||
@@ -145,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 };
|
||||
|
||||
|
@@ -97,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"), \
|
||||
|
119
Release_Notes/Exrail mods.txt
Normal file
119
Release_Notes/Exrail mods.txt
Normal 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
|
@@ -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,7 +92,11 @@ 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
|
||||
#else
|
||||
Serial2.begin(9600);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@@ -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;
|
||||
|
@@ -1,6 +1,8 @@
|
||||
/*
|
||||
* © 2022 Chris Harlow
|
||||
* © 2022-2024 Harald Barth
|
||||
* © 2023-2024 Paul M. Antoine
|
||||
* © 2024 Herb Morton
|
||||
* © 2023 Colin Murdoch
|
||||
* All rights reserved.
|
||||
*
|
||||
@@ -35,7 +37,7 @@
|
||||
|
||||
#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] = { NULL };
|
||||
@@ -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
|
||||
@@ -398,7 +408,7 @@ bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[])
|
||||
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>
|
||||
@@ -631,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
|
||||
|
@@ -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
|
||||
|
@@ -322,6 +322,15 @@ void WiThrottle::locoAction(RingStream * stream, byte* aval, char throttleChar,
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 'f': // Function key set, force function variant
|
||||
{
|
||||
bool pressed=aval[1]=='1';
|
||||
int fKey = getInt(aval+2);
|
||||
LOOPLOCOS(throttleChar, cab) {
|
||||
DCC::setFn(myLocos[loco].cab,fKey, pressed);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 'q':
|
||||
if (aval[1]=='V' || aval[1]=='R' ) { //qV or qR
|
||||
// just flag the loco for broadcast and it will happen.
|
||||
|
@@ -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,12 +253,19 @@ 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)) {
|
||||
DIAG(F("Wifi setup failed to start mDNS"));
|
||||
}
|
||||
if(!MDNS.addService("withrottle", "tcp", 2560)) {
|
||||
if(!MDNS.addService("withrottle", "tcp", port)) {
|
||||
DIAG(F("Wifi setup failed to add withrottle service to mDNS"));
|
||||
}
|
||||
|
||||
|
@@ -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
|
||||
|
@@ -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
|
||||
//
|
||||
|
@@ -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")
|
||||
|
@@ -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}
|
||||
|
53
version.h
53
version.h
@@ -3,7 +3,58 @@
|
||||
|
||||
#include "StringFormatter.h"
|
||||
|
||||
#define VERSION "5.2.45"
|
||||
#define VERSION "5.2.77"
|
||||
// 5.2.77 - Withrottle: Implement "force function" subcommand "f"
|
||||
// 5.2.76 - Bugfix: EXRAIL: Catch CV read errors in the callback
|
||||
// 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
|
||||
|
Reference in New Issue
Block a user