mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2025-03-15 18:43:06 +01:00
Compare commits
1 Commits
8313d87bac
...
9789e3b427
Author | SHA1 | Date | |
---|---|---|---|
|
9789e3b427 |
@ -310,11 +310,6 @@ void CommandDistributor::broadcastRaw(clientType type, char * msg) {
|
|||||||
broadcastReply(type, F("%s"),msg);
|
broadcastReply(type, F("%s"),msg);
|
||||||
}
|
}
|
||||||
|
|
||||||
void CommandDistributor::broadcastMessage(char * message) {
|
|
||||||
broadcastReply(COMMAND_TYPE, F("<m \"%s\">\n"),message);
|
|
||||||
broadcastReply(WITHROTTLE_TYPE, F("Hm%s\n"),message);
|
|
||||||
}
|
|
||||||
|
|
||||||
void CommandDistributor::broadcastTrackState(const FSH* format, byte trackLetter, const FSH *modename, int16_t dcAddr) {
|
void CommandDistributor::broadcastTrackState(const FSH* format, byte trackLetter, const FSH *modename, int16_t dcAddr) {
|
||||||
broadcastReply(COMMAND_TYPE, format, trackLetter, modename, dcAddr);
|
broadcastReply(COMMAND_TYPE, format, trackLetter, modename, dcAddr);
|
||||||
}
|
}
|
||||||
|
@ -60,7 +60,6 @@ public :
|
|||||||
static void forget(byte clientId);
|
static void forget(byte clientId);
|
||||||
static void broadcastRouteState(uint16_t routeId,byte state);
|
static void broadcastRouteState(uint16_t routeId,byte state);
|
||||||
static void broadcastRouteCaption(uint16_t routeId,const FSH * caption);
|
static void broadcastRouteCaption(uint16_t routeId,const FSH * caption);
|
||||||
static void broadcastMessage(char * message);
|
|
||||||
|
|
||||||
// Handling code for virtual LCD receiver.
|
// Handling code for virtual LCD receiver.
|
||||||
static Print * getVirtualLCDSerial(byte screen, byte row);
|
static Print * getVirtualLCDSerial(byte screen, byte row);
|
||||||
|
@ -65,9 +65,6 @@
|
|||||||
#ifdef EXRAIL_WARNING
|
#ifdef EXRAIL_WARNING
|
||||||
#warning You have myAutomation.h but your hardware has not enough memory to do that, so EX-RAIL DISABLED
|
#warning You have myAutomation.h but your hardware has not enough memory to do that, so EX-RAIL DISABLED
|
||||||
#endif
|
#endif
|
||||||
// compile time check, passwords 1 to 7 chars do not work, so do not try to compile with them at all
|
|
||||||
// remember trailing '\0', sizeof("") == 1.
|
|
||||||
#define PASSWDCHECK(S) static_assert(sizeof(S) == 1 || sizeof(S) > 8, "Password shorter than 8 chars")
|
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
@ -105,12 +102,10 @@ void setup()
|
|||||||
// Start Ethernet if it exists
|
// Start Ethernet if it exists
|
||||||
#ifndef ARDUINO_ARCH_ESP32
|
#ifndef ARDUINO_ARCH_ESP32
|
||||||
#if WIFI_ON
|
#if WIFI_ON
|
||||||
PASSWDCHECK(WIFI_PASSWORD); // compile time check
|
|
||||||
WifiInterface::setup(WIFI_SERIAL_LINK_SPEED, F(WIFI_SSID), F(WIFI_PASSWORD), F(WIFI_HOSTNAME), IP_PORT, WIFI_CHANNEL, WIFI_FORCE_AP);
|
WifiInterface::setup(WIFI_SERIAL_LINK_SPEED, F(WIFI_SSID), F(WIFI_PASSWORD), F(WIFI_HOSTNAME), IP_PORT, WIFI_CHANNEL, WIFI_FORCE_AP);
|
||||||
#endif // WIFI_ON
|
#endif // WIFI_ON
|
||||||
#else
|
#else
|
||||||
// ESP32 needs wifi on always
|
// ESP32 needs wifi on always
|
||||||
PASSWDCHECK(WIFI_PASSWORD); // compile time check
|
|
||||||
WifiESP::setup(WIFI_SSID, WIFI_PASSWORD, WIFI_HOSTNAME, IP_PORT, WIFI_CHANNEL, WIFI_FORCE_AP);
|
WifiESP::setup(WIFI_SSID, WIFI_PASSWORD, WIFI_HOSTNAME, IP_PORT, WIFI_CHANNEL, WIFI_FORCE_AP);
|
||||||
#endif // ARDUINO_ARCH_ESP32
|
#endif // ARDUINO_ARCH_ESP32
|
||||||
|
|
||||||
|
124
DCC.cpp
124
DCC.cpp
@ -153,22 +153,6 @@ uint8_t DCC::getThrottleSpeedByte(int cab) {
|
|||||||
return speedTable[reg].speedCode;
|
return speedTable[reg].speedCode;
|
||||||
}
|
}
|
||||||
|
|
||||||
// returns 0 to 7 for frequency
|
|
||||||
uint8_t DCC::getThrottleFrequency(int cab) {
|
|
||||||
#if defined(ARDUINO_AVR_UNO)
|
|
||||||
(void)cab;
|
|
||||||
return 0;
|
|
||||||
#else
|
|
||||||
int reg=lookupSpeedTable(cab);
|
|
||||||
if (reg<0)
|
|
||||||
return 0; // use default frequency
|
|
||||||
// shift out first 29 bits so we have the 3 "frequency bits" left
|
|
||||||
uint8_t res = (uint8_t)(speedTable[reg].functions >>29);
|
|
||||||
//DIAG(F("Speed table %d functions %l shifted %d"), reg, speedTable[reg].functions, res);
|
|
||||||
return res;
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
// returns direction on loco
|
// returns direction on loco
|
||||||
// or true/forward on "loco not found"
|
// or true/forward on "loco not found"
|
||||||
bool DCC::getThrottleDirection(int cab) {
|
bool DCC::getThrottleDirection(int cab) {
|
||||||
@ -199,55 +183,43 @@ bool DCC::setFn( int cab, int16_t functionNumber, bool on) {
|
|||||||
b[nB++] = functionNumber >>7 ; // high order bits
|
b[nB++] = functionNumber >>7 ; // high order bits
|
||||||
}
|
}
|
||||||
DCCWaveform::mainTrack.schedulePacket(b, nB, 4);
|
DCCWaveform::mainTrack.schedulePacket(b, nB, 4);
|
||||||
}
|
|
||||||
// We use the reminder table up to 28 for normal functions.
|
|
||||||
// We use 29 to 31 for DC frequency as well so up to 28
|
|
||||||
// are "real" functions and 29 to 31 are frequency bits
|
|
||||||
// controlled by function buttons
|
|
||||||
if (functionNumber > 31)
|
|
||||||
return true;
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
int reg = lookupSpeedTable(cab);
|
int reg = lookupSpeedTable(cab);
|
||||||
if (reg<0) return false;
|
if (reg<0) return false;
|
||||||
|
|
||||||
// Take care of functions:
|
// Take care of functions:
|
||||||
// Set state of function
|
// Set state of function
|
||||||
uint32_t previous=speedTable[reg].functions;
|
unsigned long previous=speedTable[reg].functions;
|
||||||
uint32_t funcmask = (1UL<<functionNumber);
|
unsigned long funcmask = (1UL<<functionNumber);
|
||||||
if (on) {
|
if (on) {
|
||||||
speedTable[reg].functions |= funcmask;
|
speedTable[reg].functions |= funcmask;
|
||||||
} else {
|
} else {
|
||||||
speedTable[reg].functions &= ~funcmask;
|
speedTable[reg].functions &= ~funcmask;
|
||||||
}
|
}
|
||||||
if (speedTable[reg].functions != previous) {
|
if (speedTable[reg].functions != previous) {
|
||||||
if (functionNumber <= 28)
|
updateGroupflags(speedTable[reg].groupFlags, functionNumber);
|
||||||
updateGroupflags(speedTable[reg].groupFlags, functionNumber);
|
|
||||||
CommandDistributor::broadcastLoco(reg);
|
CommandDistributor::broadcastLoco(reg);
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Flip function state (used from withrottle protocol)
|
// Flip function state
|
||||||
void DCC::changeFn( int cab, int16_t functionNumber) {
|
void DCC::changeFn( int cab, int16_t functionNumber) {
|
||||||
if (cab<=0 || functionNumber>31) return;
|
if (cab<=0 || functionNumber>28) return;
|
||||||
int reg = lookupSpeedTable(cab);
|
int reg = lookupSpeedTable(cab);
|
||||||
if (reg<0) return;
|
if (reg<0) return;
|
||||||
unsigned long funcmask = (1UL<<functionNumber);
|
unsigned long funcmask = (1UL<<functionNumber);
|
||||||
speedTable[reg].functions ^= funcmask;
|
speedTable[reg].functions ^= funcmask;
|
||||||
if (functionNumber <= 28) {
|
updateGroupflags(speedTable[reg].groupFlags, functionNumber);
|
||||||
updateGroupflags(speedTable[reg].groupFlags, functionNumber);
|
|
||||||
}
|
|
||||||
CommandDistributor::broadcastLoco(reg);
|
CommandDistributor::broadcastLoco(reg);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Report function state (used from withrottle protocol)
|
int DCC::getFn( int cab, int16_t functionNumber) {
|
||||||
// returns 0 false, 1 true or -1 for do not know
|
if (cab<=0 || functionNumber>28) return -1; // unknown
|
||||||
int8_t DCC::getFn( int cab, int16_t functionNumber) {
|
|
||||||
if (cab<=0 || functionNumber>31)
|
|
||||||
return -1; // unknown
|
|
||||||
int reg = lookupSpeedTable(cab);
|
int reg = lookupSpeedTable(cab);
|
||||||
if (reg<0)
|
if (reg<0) return -1;
|
||||||
return -1;
|
|
||||||
|
|
||||||
unsigned long funcmask = (1UL<<functionNumber);
|
unsigned long funcmask = (1UL<<functionNumber);
|
||||||
return (speedTable[reg].functions & funcmask)? 1 : 0;
|
return (speedTable[reg].functions & funcmask)? 1 : 0;
|
||||||
@ -325,8 +297,8 @@ preamble -0- 1 0 A7 A6 A5 A4 A3 A2 -0- 0 ^A10 ^A9 ^A8 0 A1 A0 1 -0- ....
|
|||||||
|
|
||||||
Thus in byte packet form the format is 10AAAAAA, 0AAA0AA1, 000XXXXX
|
Thus in byte packet form the format is 10AAAAAA, 0AAA0AA1, 000XXXXX
|
||||||
|
|
||||||
Die Adresse f<EFBFBD>r den ersten erweiterten Zubeh<EFBFBD>rdecoder ist wie bei den einfachen
|
Die Adresse für den ersten erweiterten Zubehördecoder ist wie bei den einfachen
|
||||||
Zubeh<EFBFBD>rdecodern die Adresse 4 = 1000-0001 0111-0001 . Diese Adresse wird in
|
Zubehördecodern die Adresse 4 = 1000-0001 0111-0001 . Diese Adresse wird in
|
||||||
Anwenderdialogen als Adresse 1 dargestellt.
|
Anwenderdialogen als Adresse 1 dargestellt.
|
||||||
|
|
||||||
This means that the first address shown to the user as "1" is mapped
|
This means that the first address shown to the user as "1" is mapped
|
||||||
@ -500,36 +472,6 @@ const ackOp FLASH READ_CV_PROG[] = {
|
|||||||
|
|
||||||
const ackOp FLASH LOCO_ID_PROG[] = {
|
const ackOp FLASH LOCO_ID_PROG[] = {
|
||||||
BASELINE,
|
BASELINE,
|
||||||
// first check cv20 for extended addressing
|
|
||||||
SETCV, (ackOp)20, // CV 19 is extended
|
|
||||||
SETBYTE, (ackOp)0,
|
|
||||||
VB, WACK, ITSKIP, // skip past extended section if cv20 is zero
|
|
||||||
// read cv20 and 19 and merge
|
|
||||||
STARTMERGE, // Setup to read cv 20
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
VB, WACK, NAKSKIP, // bad read of cv20, assume its 0
|
|
||||||
STASHLOCOID, // keep cv 20 until we have cv19 as well.
|
|
||||||
SETCV, (ackOp)19,
|
|
||||||
STARTMERGE, // Setup to read cv 19
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
V0, WACK, MERGE,
|
|
||||||
VB, WACK, NAKFAIL, // cant recover if cv 19 unreadable
|
|
||||||
COMBINE1920, // Combile byte with stash and callback
|
|
||||||
// end of advanced 20,19 check
|
|
||||||
SKIPTARGET,
|
|
||||||
SETCV, (ackOp)19, // CV 19 is consist setting
|
SETCV, (ackOp)19, // CV 19 is consist setting
|
||||||
SETBYTE, (ackOp)0,
|
SETBYTE, (ackOp)0,
|
||||||
VB, WACK, ITSKIP, // ignore consist if cv19 is zero (no consist)
|
VB, WACK, ITSKIP, // ignore consist if cv19 is zero (no consist)
|
||||||
@ -596,10 +538,6 @@ const ackOp FLASH LOCO_ID_PROG[] = {
|
|||||||
|
|
||||||
const ackOp FLASH SHORT_LOCO_ID_PROG[] = {
|
const ackOp FLASH SHORT_LOCO_ID_PROG[] = {
|
||||||
BASELINE,
|
BASELINE,
|
||||||
// Clear consist CV 19,20
|
|
||||||
SETCV,(ackOp)20,
|
|
||||||
SETBYTE, (ackOp)0,
|
|
||||||
WB,WACK, // ignore dedcoder without cv20 support
|
|
||||||
SETCV,(ackOp)19,
|
SETCV,(ackOp)19,
|
||||||
SETBYTE, (ackOp)0,
|
SETBYTE, (ackOp)0,
|
||||||
WB,WACK, // ignore dedcoder without cv19 support
|
WB,WACK, // ignore dedcoder without cv19 support
|
||||||
@ -615,25 +553,9 @@ const ackOp FLASH SHORT_LOCO_ID_PROG[] = {
|
|||||||
CALLFAIL
|
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[] = {
|
const ackOp FLASH LONG_LOCO_ID_PROG[] = {
|
||||||
BASELINE,
|
BASELINE,
|
||||||
// Clear consist CV 19,20
|
// Clear consist CV 19
|
||||||
SETCV,(ackOp)20,
|
|
||||||
SETBYTE, (ackOp)0,
|
|
||||||
WB,WACK, // ignore dedcoder without cv20 support
|
|
||||||
SETCV,(ackOp)19,
|
SETCV,(ackOp)19,
|
||||||
SETBYTE, (ackOp)0,
|
SETBYTE, (ackOp)0,
|
||||||
WB,WACK, // ignore decoder without cv19 support
|
WB,WACK, // ignore decoder without cv19 support
|
||||||
@ -702,26 +624,6 @@ void DCC::setLocoId(int id,ACK_CALLBACK callback) {
|
|||||||
DCCACK::Setup(id | 0xc000,LONG_LOCO_ID_PROG, 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
|
void DCC::forgetLoco(int cab) { // removes any speed reminders for this loco
|
||||||
setThrottle2(cab,1); // ESTOP this loco if still on track
|
setThrottle2(cab,1); // ESTOP this loco if still on track
|
||||||
int reg=lookupSpeedTable(cab, false);
|
int reg=lookupSpeedTable(cab, false);
|
||||||
|
7
DCC.h
7
DCC.h
@ -61,14 +61,13 @@ public:
|
|||||||
static void setThrottle(uint16_t cab, uint8_t tSpeed, bool tDirection);
|
static void setThrottle(uint16_t cab, uint8_t tSpeed, bool tDirection);
|
||||||
static int8_t getThrottleSpeed(int cab);
|
static int8_t getThrottleSpeed(int cab);
|
||||||
static uint8_t getThrottleSpeedByte(int cab);
|
static uint8_t getThrottleSpeedByte(int cab);
|
||||||
static uint8_t getThrottleFrequency(int cab);
|
|
||||||
static bool getThrottleDirection(int cab);
|
static bool getThrottleDirection(int cab);
|
||||||
static void writeCVByteMain(int cab, int cv, byte bValue);
|
static void writeCVByteMain(int cab, int cv, byte bValue);
|
||||||
static void writeCVBitMain(int cab, int cv, byte bNum, bool bValue);
|
static void writeCVBitMain(int cab, int cv, byte bNum, bool bValue);
|
||||||
static void setFunction(int cab, byte fByte, byte eByte);
|
static void setFunction(int cab, byte fByte, byte eByte);
|
||||||
static bool setFn(int cab, int16_t functionNumber, bool on);
|
static bool setFn(int cab, int16_t functionNumber, bool on);
|
||||||
static void changeFn(int cab, int16_t functionNumber);
|
static void changeFn(int cab, int16_t functionNumber);
|
||||||
static int8_t getFn(int cab, int16_t functionNumber);
|
static int getFn(int cab, int16_t functionNumber);
|
||||||
static uint32_t getFunctionMap(int cab);
|
static uint32_t getFunctionMap(int cab);
|
||||||
static void updateGroupflags(byte &flags, int16_t functionNumber);
|
static void updateGroupflags(byte &flags, int16_t functionNumber);
|
||||||
static void setAccessory(int address, byte port, bool gate, byte onoff = 2);
|
static void setAccessory(int address, byte port, bool gate, byte onoff = 2);
|
||||||
@ -85,7 +84,7 @@ public:
|
|||||||
|
|
||||||
static void getLocoId(ACK_CALLBACK callback);
|
static void getLocoId(ACK_CALLBACK callback);
|
||||||
static void setLocoId(int id,ACK_CALLBACK callback);
|
static void setLocoId(int id,ACK_CALLBACK callback);
|
||||||
static void setConsistId(int id,bool reverse,ACK_CALLBACK callback);
|
|
||||||
// Enhanced API functions
|
// Enhanced API functions
|
||||||
static void forgetLoco(int cab); // removes any speed reminders for this loco
|
static void forgetLoco(int cab); // removes any speed reminders for this loco
|
||||||
static void forgetAllLocos(); // removes all speed reminders
|
static void forgetAllLocos(); // removes all speed reminders
|
||||||
@ -100,7 +99,7 @@ public:
|
|||||||
int loco;
|
int loco;
|
||||||
byte speedCode;
|
byte speedCode;
|
||||||
byte groupFlags;
|
byte groupFlags;
|
||||||
uint32_t functions;
|
unsigned long functions;
|
||||||
};
|
};
|
||||||
static LOCO speedTable[MAX_LOCOS];
|
static LOCO speedTable[MAX_LOCOS];
|
||||||
static int lookupSpeedTable(int locoId, bool autoCreate=true);
|
static int lookupSpeedTable(int locoId, bool autoCreate=true);
|
||||||
|
29
DCCACK.cpp
29
DCCACK.cpp
@ -27,8 +27,8 @@
|
|||||||
#include "DCCWaveform.h"
|
#include "DCCWaveform.h"
|
||||||
#include "TrackManager.h"
|
#include "TrackManager.h"
|
||||||
|
|
||||||
unsigned long DCCACK::minAckPulseDuration = 2000; // micros
|
unsigned int DCCACK::minAckPulseDuration = 2000; // micros
|
||||||
unsigned long DCCACK::maxAckPulseDuration = 20000; // micros
|
unsigned int DCCACK::maxAckPulseDuration = 20000; // micros
|
||||||
|
|
||||||
MotorDriver * DCCACK::progDriver=NULL;
|
MotorDriver * DCCACK::progDriver=NULL;
|
||||||
ackOp const * DCCACK::ackManagerProg;
|
ackOp const * DCCACK::ackManagerProg;
|
||||||
@ -50,8 +50,8 @@ volatile uint8_t DCCACK::numAckSamples=0;
|
|||||||
uint8_t DCCACK::trailingEdgeCounter=0;
|
uint8_t DCCACK::trailingEdgeCounter=0;
|
||||||
|
|
||||||
|
|
||||||
unsigned long DCCACK::ackPulseDuration; // micros
|
unsigned int DCCACK::ackPulseDuration; // micros
|
||||||
unsigned long DCCACK::ackPulseStart; // micros
|
unsigned long DCCACK::ackPulseStart; // micros
|
||||||
volatile bool DCCACK::ackDetected;
|
volatile bool DCCACK::ackDetected;
|
||||||
unsigned long DCCACK::ackCheckStart; // millis
|
unsigned long DCCACK::ackCheckStart; // millis
|
||||||
volatile bool DCCACK::ackPending;
|
volatile bool DCCACK::ackPending;
|
||||||
@ -127,7 +127,7 @@ bool DCCACK::checkResets(uint8_t numResets) {
|
|||||||
void DCCACK::setAckBaseline() {
|
void DCCACK::setAckBaseline() {
|
||||||
int baseline=progDriver->getCurrentRaw();
|
int baseline=progDriver->getCurrentRaw();
|
||||||
ackThreshold= baseline + progDriver->mA2raw(ackLimitmA);
|
ackThreshold= baseline + progDriver->mA2raw(ackLimitmA);
|
||||||
if (Diag::ACK) DIAG(F("ACK baseline=%d/%dmA Threshold=%d/%dmA Duration between %lus and %lus"),
|
if (Diag::ACK) DIAG(F("ACK baseline=%d/%dmA Threshold=%d/%dmA Duration between %uus and %uus"),
|
||||||
baseline,progDriver->raw2mA(baseline),
|
baseline,progDriver->raw2mA(baseline),
|
||||||
ackThreshold,progDriver->raw2mA(ackThreshold),
|
ackThreshold,progDriver->raw2mA(ackThreshold),
|
||||||
minAckPulseDuration, maxAckPulseDuration);
|
minAckPulseDuration, maxAckPulseDuration);
|
||||||
@ -146,7 +146,7 @@ void DCCACK::setAckPending() {
|
|||||||
|
|
||||||
byte DCCACK::getAck() {
|
byte DCCACK::getAck() {
|
||||||
if (ackPending) return (2); // still waiting
|
if (ackPending) return (2); // still waiting
|
||||||
if (Diag::ACK) DIAG(F("%S after %dmS max=%d/%dmA pulse=%luS samples=%d gaps=%d"),ackDetected?F("ACK"):F("NO-ACK"), ackCheckDuration,
|
if (Diag::ACK) DIAG(F("%S after %dmS max=%d/%dmA pulse=%uuS samples=%d gaps=%d"),ackDetected?F("ACK"):F("NO-ACK"), ackCheckDuration,
|
||||||
ackMaxCurrent,progDriver->raw2mA(ackMaxCurrent), ackPulseDuration, numAckSamples, numAckGaps);
|
ackMaxCurrent,progDriver->raw2mA(ackMaxCurrent), ackPulseDuration, numAckSamples, numAckGaps);
|
||||||
if (ackDetected) return (1); // Yes we had an ack
|
if (ackDetected) return (1); // Yes we had an ack
|
||||||
return(0); // pending set off but not detected means no ACK.
|
return(0); // pending set off but not detected means no ACK.
|
||||||
@ -314,14 +314,6 @@ void DCCACK::loop() {
|
|||||||
callback( LONG_ADDR_MARKER | ( ackManagerByte + ((ackManagerStash - 192) << 8)));
|
callback( LONG_ADDR_MARKER | ( ackManagerByte + ((ackManagerStash - 192) << 8)));
|
||||||
return;
|
return;
|
||||||
|
|
||||||
case COMBINE1920:
|
|
||||||
// ackManagerStash is cv20, ackManagerByte is CV 19
|
|
||||||
// This will not be called if cv20==0
|
|
||||||
ackManagerByte &= 0x7F; // ignore direction marker
|
|
||||||
ackManagerByte %=100; // take last 2 decimal digits
|
|
||||||
callback( ackManagerStash*100+ackManagerByte);
|
|
||||||
return;
|
|
||||||
|
|
||||||
case ITSKIP:
|
case ITSKIP:
|
||||||
if (!ackReceived) break;
|
if (!ackReceived) break;
|
||||||
// SKIP opcodes until SKIPTARGET found
|
// SKIP opcodes until SKIPTARGET found
|
||||||
@ -330,15 +322,6 @@ void DCCACK::loop() {
|
|||||||
opcode=GETFLASH(ackManagerProg);
|
opcode=GETFLASH(ackManagerProg);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case NAKSKIP:
|
|
||||||
if (ackReceived) break;
|
|
||||||
// SKIP opcodes until SKIPTARGET found
|
|
||||||
while (opcode!=SKIPTARGET) {
|
|
||||||
ackManagerProg++;
|
|
||||||
opcode=GETFLASH(ackManagerProg);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case SKIPTARGET:
|
case SKIPTARGET:
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
|
12
DCCACK.h
12
DCCACK.h
@ -56,8 +56,6 @@ enum ackOp : byte
|
|||||||
STASHLOCOID, // keeps current byte value for later
|
STASHLOCOID, // keeps current byte value for later
|
||||||
COMBINELOCOID, // combines current value with stashed value and returns it
|
COMBINELOCOID, // combines current value with stashed value and returns it
|
||||||
ITSKIP, // skip to SKIPTARGET if ack true
|
ITSKIP, // skip to SKIPTARGET if ack true
|
||||||
NAKSKIP, // skip to SKIPTARGET if ack false
|
|
||||||
COMBINE1920, // combine cvs 19 and 20 and callback
|
|
||||||
SKIPTARGET = 0xFF // jump to target
|
SKIPTARGET = 0xFF // jump to target
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -79,10 +77,10 @@ class DCCACK {
|
|||||||
static inline void setAckLimit(int mA) {
|
static inline void setAckLimit(int mA) {
|
||||||
ackLimitmA = mA;
|
ackLimitmA = mA;
|
||||||
}
|
}
|
||||||
static inline void setMinAckPulseDuration(unsigned long i) {
|
static inline void setMinAckPulseDuration(unsigned int i) {
|
||||||
minAckPulseDuration = i;
|
minAckPulseDuration = i;
|
||||||
}
|
}
|
||||||
static inline void setMaxAckPulseDuration(unsigned long i) {
|
static inline void setMaxAckPulseDuration(unsigned int i) {
|
||||||
maxAckPulseDuration = i;
|
maxAckPulseDuration = i;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -126,11 +124,11 @@ class DCCACK {
|
|||||||
static unsigned long ackCheckStart; // millis
|
static unsigned long ackCheckStart; // millis
|
||||||
static unsigned int ackCheckDuration; // millis
|
static unsigned int ackCheckDuration; // millis
|
||||||
|
|
||||||
static unsigned long ackPulseDuration; // micros
|
static unsigned int ackPulseDuration; // micros
|
||||||
static unsigned long ackPulseStart; // micros
|
static unsigned long ackPulseStart; // micros
|
||||||
|
|
||||||
static unsigned long minAckPulseDuration ; // micros
|
static unsigned int minAckPulseDuration ; // micros
|
||||||
static unsigned long maxAckPulseDuration ; // micros
|
static unsigned int maxAckPulseDuration ; // micros
|
||||||
static MotorDriver* progDriver;
|
static MotorDriver* progDriver;
|
||||||
static volatile uint8_t numAckGaps;
|
static volatile uint8_t numAckGaps;
|
||||||
static volatile uint8_t numAckSamples;
|
static volatile uint8_t numAckSamples;
|
||||||
|
@ -68,10 +68,10 @@ Once a new OPCODE is decided upon, update this list.
|
|||||||
K, Reserved for future use - Potentially Railcom
|
K, Reserved for future use - Potentially Railcom
|
||||||
l, Loco speedbyte/function map broadcast
|
l, Loco speedbyte/function map broadcast
|
||||||
L, Reserved for LCC interface (implemented in EXRAIL)
|
L, Reserved for LCC interface (implemented in EXRAIL)
|
||||||
m, message to throttles broadcast
|
m,
|
||||||
M, Write DCC packet
|
M, Write DCC packet
|
||||||
n, Reserved for SensorCam
|
n,
|
||||||
N, Reserved for Sensorcam
|
N,
|
||||||
o,
|
o,
|
||||||
O, Output broadcast
|
O, Output broadcast
|
||||||
p, Broadcast power state
|
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 on main
|
||||||
W, Write CV
|
W, Write CV
|
||||||
x,
|
x,
|
||||||
X, Invalid command response
|
X, Invalid command
|
||||||
y,
|
y,
|
||||||
Y, Output broadcast
|
Y, Output broadcast
|
||||||
z, Direct output
|
z,
|
||||||
Z, Output configuration/control
|
Z, Output configuration/control
|
||||||
*/
|
*/
|
||||||
|
|
||||||
@ -283,22 +283,25 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
|
|||||||
return; // filterCallback asked us to ignore
|
return; // filterCallback asked us to ignore
|
||||||
case 't': // THROTTLE <t [REGISTER] CAB SPEED DIRECTION>
|
case 't': // THROTTLE <t [REGISTER] CAB SPEED DIRECTION>
|
||||||
{
|
{
|
||||||
|
if (params==1) { // <t cab> display state
|
||||||
|
|
||||||
|
int16_t slot=DCC::lookupSpeedTable(p[0],false);
|
||||||
|
if (slot>=0) {
|
||||||
|
DCC::LOCO * sp=&DCC::speedTable[slot];
|
||||||
|
StringFormatter::send(stream,F("<l %d %d %d %l>\n"),
|
||||||
|
sp->loco,slot,sp->speedCode,sp->functions);
|
||||||
|
}
|
||||||
|
else // send dummy state speed 0 fwd no functions.
|
||||||
|
StringFormatter::send(stream,F("<l %d -1 128 0>\n"),p[0]);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
int16_t cab;
|
int16_t cab;
|
||||||
int16_t tspeed;
|
int16_t tspeed;
|
||||||
int16_t direction;
|
int16_t direction;
|
||||||
|
|
||||||
if (params==1) { // <t cab> display state
|
|
||||||
int16_t slot=DCC::lookupSpeedTable(p[0],false);
|
|
||||||
if (slot>=0)
|
|
||||||
CommandDistributor::broadcastLoco(slot);
|
|
||||||
else // send dummy state speed 0 fwd no functions.
|
|
||||||
StringFormatter::send(stream,F("<l %d -1 128 0>\n"),p[0]);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (params == 4)
|
if (params == 4)
|
||||||
{ // <t REGISTER CAB SPEED DIRECTION>
|
{ // <t REGISTER CAB SPEED DIRECTION>
|
||||||
// ignore register p[0]
|
|
||||||
cab = p[1];
|
cab = p[1];
|
||||||
tspeed = p[2];
|
tspeed = p[2];
|
||||||
direction = p[3];
|
direction = p[3];
|
||||||
@ -458,9 +461,6 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
|
|||||||
DCC::setLocoId(p[0],callback_Wloco);
|
DCC::setLocoId(p[0],callback_Wloco);
|
||||||
else if (params == 4) // WRITE CV ON PROG <W CV VALUE [CALLBACKNUM] [CALLBACKSUB]>
|
else if (params == 4) // WRITE CV ON PROG <W CV VALUE [CALLBACKNUM] [CALLBACKSUB]>
|
||||||
DCC::writeCVByte(p[0], p[1], callback_W4);
|
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>
|
else if (params == 2) // WRITE CV ON PROG <W CV VALUE>
|
||||||
DCC::writeCVByte(p[0], p[1], callback_W);
|
DCC::writeCVByte(p[0], p[1], callback_W);
|
||||||
else
|
else
|
||||||
@ -582,13 +582,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
|
|||||||
DCC::setThrottle(0,1,1); // this broadcasts speed 1(estop) and sets all reminders to speed 1.
|
DCC::setThrottle(0,1,1); // this broadcasts speed 1(estop) and sets all reminders to speed 1.
|
||||||
return;
|
return;
|
||||||
|
|
||||||
#ifdef HAS_ENOUGH_MEMORY
|
|
||||||
case 'c': // SEND METER RESPONSES <c>
|
case 'c': // SEND METER RESPONSES <c>
|
||||||
// No longer useful because of multiple tracks See <JG> and <JI>
|
// No longer useful because of multiple tracks See <JG> and <JI>
|
||||||
if (params>0) break;
|
if (params>0) break;
|
||||||
TrackManager::reportObsoleteCurrent(stream);
|
TrackManager::reportObsoleteCurrent(stream);
|
||||||
return;
|
return;
|
||||||
#endif
|
|
||||||
case 'Q': // SENSORS <Q>
|
case 'Q': // SENSORS <Q>
|
||||||
Sensor::printAll(stream);
|
Sensor::printAll(stream);
|
||||||
return;
|
return;
|
||||||
@ -800,7 +799,6 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
|
|||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
case '/': // implemented in EXRAIL parser
|
|
||||||
case 'L': // LCC interface implemented in EXRAIL parser
|
case 'L': // LCC interface implemented in EXRAIL parser
|
||||||
break; // Will <X> if not intercepted by EXRAIL
|
break; // Will <X> if not intercepted by EXRAIL
|
||||||
|
|
||||||
@ -1073,24 +1071,15 @@ bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) {
|
|||||||
#ifndef DISABLE_PROG
|
#ifndef DISABLE_PROG
|
||||||
case "ACK"_hk: // <D ACK ON/OFF> <D ACK [LIMIT|MIN|MAX|RETRY] Value>
|
case "ACK"_hk: // <D ACK ON/OFF> <D ACK [LIMIT|MIN|MAX|RETRY] Value>
|
||||||
if (params >= 3) {
|
if (params >= 3) {
|
||||||
long duration;
|
|
||||||
if (p[1] == "LIMIT"_hk) {
|
if (p[1] == "LIMIT"_hk) {
|
||||||
DCCACK::setAckLimit(p[2]);
|
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) {
|
} else if (p[1] == "MIN"_hk) {
|
||||||
if (params == 4 && p[3] == "MS"_hk)
|
DCCACK::setMinAckPulseDuration(p[2]);
|
||||||
duration = p[2] * 1000L;
|
LCD(0, F("Ack Min=%uus"), p[2]); // <D ACK MIN 1500>
|
||||||
else
|
|
||||||
duration = p[2];
|
|
||||||
DCCACK::setMinAckPulseDuration(duration);
|
|
||||||
LCD(0, F("Ack Min=%lus"), duration); // <D ACK MIN 1500>
|
|
||||||
} else if (p[1] == "MAX"_hk) {
|
} else if (p[1] == "MAX"_hk) {
|
||||||
if (params == 4 && p[3] == "MS"_hk) // <D ACK MAX 80 MS>
|
DCCACK::setMaxAckPulseDuration(p[2]);
|
||||||
duration = p[2] * 1000L;
|
LCD(0, F("Ack Max=%uus"), p[2]); // <D ACK MAX 9000>
|
||||||
else
|
|
||||||
duration = p[2];
|
|
||||||
DCCACK::setMaxAckPulseDuration(duration);
|
|
||||||
LCD(0, F("Ack Max=%lus"), duration); // <D ACK MAX 9000>
|
|
||||||
} else if (p[1] == "RETRY"_hk) {
|
} else if (p[1] == "RETRY"_hk) {
|
||||||
if (p[2] >255) p[2]=3;
|
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>
|
LCD(0, F("Ack Retry=%d Sum=%d"), p[2], DCCACK::setAckRetry(p[2])); // <D ACK RETRY 2>
|
||||||
@ -1360,11 +1349,3 @@ void DCCEXParser::callback_Wloco(int16_t result)
|
|||||||
StringFormatter::send(getAsyncReplyStream(), F("<w %d>\n"), result);
|
StringFormatter::send(getAsyncReplyStream(), F("<w %d>\n"), result);
|
||||||
commitAsyncReplyStream();
|
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,7 +71,6 @@ struct DCCEXParser
|
|||||||
static void callback_R(int16_t result);
|
static void callback_R(int16_t result);
|
||||||
static void callback_Rloco(int16_t result);
|
static void callback_Rloco(int16_t result);
|
||||||
static void callback_Wloco(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_Vbit(int16_t result);
|
||||||
static void callback_Vbyte(int16_t result);
|
static void callback_Vbyte(int16_t result);
|
||||||
static FILTER_CALLBACK filterCallback;
|
static FILTER_CALLBACK filterCallback;
|
||||||
|
11
DCCTimer.h
11
DCCTimer.h
@ -1,5 +1,5 @@
|
|||||||
/*
|
/*
|
||||||
* © 2022-2024 Paul M. Antoine
|
* © 2022-2023 Paul M. Antoine
|
||||||
* © 2021 Mike S
|
* © 2021 Mike S
|
||||||
* © 2021-2023 Harald Barth
|
* © 2021-2023 Harald Barth
|
||||||
* © 2021 Fred Decker
|
* © 2021 Fred Decker
|
||||||
@ -65,11 +65,7 @@ class DCCTimer {
|
|||||||
static void startRailcomTimer(byte brakePin);
|
static void startRailcomTimer(byte brakePin);
|
||||||
static void ackRailcomTimer();
|
static void ackRailcomTimer();
|
||||||
static void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency);
|
static void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency);
|
||||||
static void DCCEXanalogWrite(uint8_t pin, int value, bool invert);
|
static void DCCEXanalogWrite(uint8_t pin, int value);
|
||||||
static void DCCEXledcDetachPin(uint8_t pin);
|
|
||||||
static void DCCEXanalogCopyChannel(int8_t frompin, int8_t topin);
|
|
||||||
static void DCCEXInrushControlOn(uint8_t pin, int duty, bool invert);
|
|
||||||
static void DCCEXledcAttachPin(uint8_t pin, int8_t channel, bool inverted);
|
|
||||||
|
|
||||||
// Update low ram level. Allow for extra bytes to be specified
|
// Update low ram level. Allow for extra bytes to be specified
|
||||||
// by estimation or inspection, that may be used by other
|
// by estimation or inspection, that may be used by other
|
||||||
@ -91,7 +87,6 @@ class DCCTimer {
|
|||||||
static void reset();
|
static void reset();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static void DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency);
|
|
||||||
static int freeMemory();
|
static int freeMemory();
|
||||||
static volatile int minimum_free_memory;
|
static volatile int minimum_free_memory;
|
||||||
static const int DCC_SIGNAL_TIME=58; // this is the 58uS DCC 1-bit waveform half-cycle
|
static const int DCC_SIGNAL_TIME=58; // this is the 58uS DCC 1-bit waveform half-cycle
|
||||||
@ -135,8 +130,6 @@ private:
|
|||||||
#if defined (ARDUINO_ARCH_STM32)
|
#if defined (ARDUINO_ARCH_STM32)
|
||||||
// bit array of used pins (max 32)
|
// bit array of used pins (max 32)
|
||||||
static uint32_t usedpins;
|
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
|
#else
|
||||||
// bit array of used pins (max 16)
|
// bit array of used pins (max 16)
|
||||||
static uint16_t usedpins;
|
static uint16_t usedpins;
|
||||||
|
@ -29,7 +29,6 @@
|
|||||||
#include <avr/boot.h>
|
#include <avr/boot.h>
|
||||||
#include <avr/wdt.h>
|
#include <avr/wdt.h>
|
||||||
#include "DCCTimer.h"
|
#include "DCCTimer.h"
|
||||||
#include "DIAG.h"
|
|
||||||
#ifdef DEBUG_ADC
|
#ifdef DEBUG_ADC
|
||||||
#include "TrackManager.h"
|
#include "TrackManager.h"
|
||||||
#endif
|
#endif
|
||||||
@ -185,88 +184,11 @@ int DCCTimer::freeMemory() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::reset() {
|
void DCCTimer::reset() {
|
||||||
// 250ms chosen to circumwent bootloader bug which
|
wdt_enable( WDTO_15MS); // set Arduino watchdog timer for 15ms
|
||||||
// hangs at too short timepout (like 15ms)
|
delay(50); // wait for the prescaller time to expire
|
||||||
wdt_enable( WDTO_250MS); // set Arduino watchdog timer for 250ms
|
|
||||||
delay(500); // wait for it to happen
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f);
|
|
||||||
}
|
|
||||||
void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) {
|
|
||||||
#if defined(ARDUINO_AVR_UNO)
|
|
||||||
// Not worth doin something here as:
|
|
||||||
// If we are on pin 9 or 10 we are on Timer1 and we can not touch Timer1 as that is our DCC source.
|
|
||||||
// If we are on pin 5 or 6 we are on Timer 0 ad we can not touch Timer0 as that is millis() etc.
|
|
||||||
// We are most likely not on pin 3 or 11 as no known motor shield has that as brake.
|
|
||||||
#endif
|
|
||||||
#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)
|
|
||||||
// Speed mapping is done like this:
|
|
||||||
// No functions buttons: 000 0 -> low 131Hz
|
|
||||||
// Only F29 pressed 001 1 -> mid 490Hz
|
|
||||||
// F30 with or w/o F29 01x 2-3 -> high 3400Hz
|
|
||||||
// F31 with or w/o F29/30 1xx 4-7 -> supersonic 62500Hz
|
|
||||||
uint8_t abits;
|
|
||||||
uint8_t bbits;
|
|
||||||
if (pin == 9 || pin == 10) { // timer 2 is different
|
|
||||||
|
|
||||||
if (fbits >= 4)
|
|
||||||
abits = B00000011;
|
|
||||||
else
|
|
||||||
abits = B00000001;
|
|
||||||
|
|
||||||
if (fbits >= 4)
|
|
||||||
bbits = B0001;
|
|
||||||
else if (fbits >= 2)
|
|
||||||
bbits = B0010;
|
|
||||||
else if (fbits == 1)
|
|
||||||
bbits = B0100;
|
|
||||||
else // fbits == 0
|
|
||||||
bbits = B0110;
|
|
||||||
|
|
||||||
TCCR2A = (TCCR2A & B11111100) | abits; // set WGM0 and WGM1
|
|
||||||
TCCR2B = (TCCR2B & B11110000) | bbits; // set WGM2 and 3 bits of prescaler
|
|
||||||
DIAG(F("Timer 2 A=%x B=%x"), TCCR2A, TCCR2B);
|
|
||||||
|
|
||||||
} else { // not timer 9 or 10
|
|
||||||
abits = B01;
|
|
||||||
|
|
||||||
if (fbits >= 4)
|
|
||||||
bbits = B1001;
|
|
||||||
else if (fbits >= 2)
|
|
||||||
bbits = B0010;
|
|
||||||
else if (fbits == 1)
|
|
||||||
bbits = B0011;
|
|
||||||
else
|
|
||||||
bbits = B0100;
|
|
||||||
|
|
||||||
switch (pin) {
|
|
||||||
// case 9 and 10 taken care of above by if()
|
|
||||||
case 6:
|
|
||||||
case 7:
|
|
||||||
case 8:
|
|
||||||
// Timer4
|
|
||||||
TCCR4A = (TCCR4A & B11111100) | abits; // set WGM0 and WGM1
|
|
||||||
TCCR4B = (TCCR4B & B11100000) | bbits; // set WGM2 and WGM3 and divisor
|
|
||||||
//DIAG(F("Timer 4 A=%x B=%x"), TCCR4A, TCCR4B);
|
|
||||||
break;
|
|
||||||
case 46:
|
|
||||||
case 45:
|
|
||||||
case 44:
|
|
||||||
// Timer5
|
|
||||||
TCCR5A = (TCCR5A & B11111100) | abits; // set WGM0 and WGM1
|
|
||||||
TCCR5B = (TCCR5B & B11100000) | bbits; // set WGM2 and WGM3 and divisor
|
|
||||||
//DIAG(F("Timer 5 A=%x B=%x"), TCCR5A, TCCR5B);
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)
|
#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)
|
||||||
#define NUM_ADC_INPUTS 16
|
#define NUM_ADC_INPUTS 16
|
||||||
#else
|
#else
|
||||||
|
126
DCCTimerESP.cpp
126
DCCTimerESP.cpp
@ -76,14 +76,8 @@ int DCCTimer::freeMemory() {
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
#ifdef ARDUINO_ARCH_ESP32
|
#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 <driver/adc.h>
|
||||||
#include <soc/sens_reg.h>
|
#include <soc/sens_reg.h>
|
||||||
#include <soc/sens_struct.h>
|
#include <soc/sens_struct.h>
|
||||||
@ -157,28 +151,10 @@ void DCCTimer::reset() {
|
|||||||
ESP.restart();
|
ESP.restart();
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
|
|
||||||
if (f >= 16)
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f);
|
|
||||||
/*
|
|
||||||
else if (f == 7) // not used on ESP32
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 62500);
|
|
||||||
*/
|
|
||||||
else if (f >= 4)
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 32000);
|
|
||||||
else if (f >= 3)
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 16000);
|
|
||||||
else if (f >= 2)
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 3400);
|
|
||||||
else if (f == 1)
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 480);
|
|
||||||
else
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 131);
|
|
||||||
}
|
|
||||||
|
|
||||||
#include "esp32-hal.h"
|
#include "esp32-hal.h"
|
||||||
#include "soc/soc_caps.h"
|
#include "soc/soc_caps.h"
|
||||||
|
|
||||||
|
|
||||||
#ifdef SOC_LEDC_SUPPORT_HS_MODE
|
#ifdef SOC_LEDC_SUPPORT_HS_MODE
|
||||||
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM<<1)
|
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM<<1)
|
||||||
#else
|
#else
|
||||||
@ -188,7 +164,7 @@ void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
|
|||||||
static int8_t pin_to_channel[SOC_GPIO_PIN_COUNT] = { 0 };
|
static int8_t pin_to_channel[SOC_GPIO_PIN_COUNT] = { 0 };
|
||||||
static int cnt_channel = LEDC_CHANNELS;
|
static int cnt_channel = LEDC_CHANNELS;
|
||||||
|
|
||||||
void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency) {
|
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency) {
|
||||||
if (pin < SOC_GPIO_PIN_COUNT) {
|
if (pin < SOC_GPIO_PIN_COUNT) {
|
||||||
if (pin_to_channel[pin] != 0) {
|
if (pin_to_channel[pin] != 0) {
|
||||||
ledcSetup(pin_to_channel[pin], frequency, 8);
|
ledcSetup(pin_to_channel[pin], frequency, 8);
|
||||||
@ -196,113 +172,27 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::DCCEXledcDetachPin(uint8_t pin) {
|
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
|
||||||
DIAG(F("Clear pin %d channel"), pin);
|
|
||||||
pin_to_channel[pin] = 0;
|
|
||||||
pinMatrixOutDetach(pin, false, false);
|
|
||||||
}
|
|
||||||
|
|
||||||
static byte LEDCToMux[] = {
|
|
||||||
LEDC_HS_SIG_OUT0_IDX,
|
|
||||||
LEDC_HS_SIG_OUT1_IDX,
|
|
||||||
LEDC_HS_SIG_OUT2_IDX,
|
|
||||||
LEDC_HS_SIG_OUT3_IDX,
|
|
||||||
LEDC_HS_SIG_OUT4_IDX,
|
|
||||||
LEDC_HS_SIG_OUT5_IDX,
|
|
||||||
LEDC_HS_SIG_OUT6_IDX,
|
|
||||||
LEDC_HS_SIG_OUT7_IDX,
|
|
||||||
LEDC_LS_SIG_OUT0_IDX,
|
|
||||||
LEDC_LS_SIG_OUT1_IDX,
|
|
||||||
LEDC_LS_SIG_OUT2_IDX,
|
|
||||||
LEDC_LS_SIG_OUT3_IDX,
|
|
||||||
LEDC_LS_SIG_OUT4_IDX,
|
|
||||||
LEDC_LS_SIG_OUT5_IDX,
|
|
||||||
LEDC_LS_SIG_OUT6_IDX,
|
|
||||||
LEDC_LS_SIG_OUT7_IDX,
|
|
||||||
};
|
|
||||||
|
|
||||||
void DCCTimer::DCCEXledcAttachPin(uint8_t pin, int8_t channel, bool inverted) {
|
|
||||||
DIAG(F("Attaching pin %d to channel %d %c"), pin, channel, inverted ? 'I' : ' ');
|
|
||||||
ledcAttachPin(pin, channel);
|
|
||||||
if (inverted) // we attach again but with inversion
|
|
||||||
gpio_matrix_out(pin, LEDCToMux[channel], inverted, 0);
|
|
||||||
}
|
|
||||||
|
|
||||||
void DCCTimer::DCCEXanalogCopyChannel(int8_t frompin, int8_t topin) {
|
|
||||||
// arguments are signed depending on inversion of pins
|
|
||||||
DIAG(F("Pin %d copied to %d"), frompin, topin);
|
|
||||||
bool inverted = false;
|
|
||||||
if (frompin<0)
|
|
||||||
frompin = -frompin;
|
|
||||||
if (topin<0) {
|
|
||||||
inverted = true;
|
|
||||||
topin = -topin;
|
|
||||||
}
|
|
||||||
int channel = pin_to_channel[frompin]; // after abs(frompin)
|
|
||||||
pin_to_channel[topin] = channel;
|
|
||||||
DCCTimer::DCCEXledcAttachPin(topin, channel, inverted);
|
|
||||||
}
|
|
||||||
|
|
||||||
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value, bool invert) {
|
|
||||||
// This allocates channels 15, 13, 11, ....
|
|
||||||
// so each channel gets its own timer.
|
|
||||||
if (pin < SOC_GPIO_PIN_COUNT) {
|
if (pin < SOC_GPIO_PIN_COUNT) {
|
||||||
if (pin_to_channel[pin] == 0) {
|
if (pin_to_channel[pin] == 0) {
|
||||||
int search_channel;
|
|
||||||
int n;
|
|
||||||
if (!cnt_channel) {
|
if (!cnt_channel) {
|
||||||
log_e("No more PWM channels available! All %u already used", LEDC_CHANNELS);
|
log_e("No more PWM channels available! All %u already used", LEDC_CHANNELS);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
// search for free channels top down
|
pin_to_channel[pin] = --cnt_channel;
|
||||||
for (search_channel=LEDC_CHANNELS-1; search_channel >=cnt_channel; search_channel -= 2) {
|
ledcSetup(cnt_channel, 1000, 8);
|
||||||
bool chanused = false;
|
ledcAttachPin(pin, cnt_channel);
|
||||||
for (n=0; n < SOC_GPIO_PIN_COUNT; n++) {
|
|
||||||
if (pin_to_channel[n] == search_channel) { // current search_channel used
|
|
||||||
chanused = true;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if (chanused)
|
|
||||||
continue;
|
|
||||||
if (n == SOC_GPIO_PIN_COUNT) // current search_channel unused
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
if (search_channel >= cnt_channel) {
|
|
||||||
pin_to_channel[pin] = search_channel;
|
|
||||||
DIAG(F("Pin %d assigned to search channel %d"), pin, search_channel);
|
|
||||||
} else {
|
|
||||||
pin_to_channel[pin] = --cnt_channel; // This sets 15, 13, ...
|
|
||||||
DIAG(F("Pin %d assigned to new channel %d"), pin, cnt_channel);
|
|
||||||
--cnt_channel; // Now we are at 14, 12, ...
|
|
||||||
}
|
|
||||||
ledcSetup(pin_to_channel[pin], 1000, 8);
|
|
||||||
DCCEXledcAttachPin(pin, pin_to_channel[pin], invert);
|
|
||||||
} else {
|
} else {
|
||||||
// This else is only here so we can enable diag
|
ledcAttachPin(pin, pin_to_channel[pin]);
|
||||||
// Pin should be already attached to channel
|
|
||||||
// DIAG(F("Pin %d assigned to old channel %d"), pin, pin_to_channel[pin]);
|
|
||||||
}
|
}
|
||||||
ledcWrite(pin_to_channel[pin], value);
|
ledcWrite(pin_to_channel[pin], value);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::DCCEXInrushControlOn(uint8_t pin, int duty, bool inverted) {
|
|
||||||
// this uses hardcoded channel 0
|
|
||||||
ledcSetup(0, 62500, 8);
|
|
||||||
DCCEXledcAttachPin(pin, 0, inverted);
|
|
||||||
ledcWrite(0, duty);
|
|
||||||
}
|
|
||||||
|
|
||||||
int ADCee::init(uint8_t pin) {
|
int ADCee::init(uint8_t pin) {
|
||||||
pinMode(pin, ANALOG);
|
pinMode(pin, ANALOG);
|
||||||
adc1_config_width(ADC_WIDTH_BIT_12);
|
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);
|
adc1_config_channel_atten(pinToADC1Channel(pin),ADC_ATTEN_DB_11);
|
||||||
#endif
|
|
||||||
return adc1_get_raw(pinToADC1Channel(pin));
|
return adc1_get_raw(pinToADC1Channel(pin));
|
||||||
}
|
}
|
||||||
int16_t ADCee::ADCmax() {
|
int16_t ADCee::ADCmax() {
|
||||||
|
@ -134,11 +134,6 @@ void DCCTimer::reset() {
|
|||||||
while(true){}
|
while(true){}
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
|
|
||||||
}
|
|
||||||
void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) {
|
|
||||||
}
|
|
||||||
|
|
||||||
int16_t ADCee::ADCmax() {
|
int16_t ADCee::ADCmax() {
|
||||||
return 4095;
|
return 4095;
|
||||||
}
|
}
|
||||||
|
@ -165,11 +165,6 @@ void DCCTimer::reset() {
|
|||||||
while(true) {};
|
while(true) {};
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
|
|
||||||
}
|
|
||||||
void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) {
|
|
||||||
}
|
|
||||||
|
|
||||||
#define NUM_ADC_INPUTS NUM_ANALOG_INPUTS
|
#define NUM_ADC_INPUTS NUM_ANALOG_INPUTS
|
||||||
|
|
||||||
uint16_t ADCee::usedpins = 0;
|
uint16_t ADCee::usedpins = 0;
|
||||||
|
@ -1,6 +1,6 @@
|
|||||||
/*
|
/*
|
||||||
* © 2023 Neil McKechnie
|
* © 2023 Neil McKechnie
|
||||||
* © 2022-2024 Paul M. Antoine
|
* © 2022-2023 Paul M. Antoine
|
||||||
* © 2021 Mike S
|
* © 2021 Mike S
|
||||||
* © 2021, 2023 Harald Barth
|
* © 2021, 2023 Harald Barth
|
||||||
* © 2021 Fred Decker
|
* © 2021 Fred Decker
|
||||||
@ -34,22 +34,8 @@
|
|||||||
#include "TrackManager.h"
|
#include "TrackManager.h"
|
||||||
#endif
|
#endif
|
||||||
#include "DIAG.h"
|
#include "DIAG.h"
|
||||||
#include <wiring_private.h>
|
|
||||||
|
|
||||||
#if defined(ARDUINO_NUCLEO_F401RE)
|
#if defined(ARDUINO_NUCLEO_F401RE) || defined(ARDUINO_NUCLEO_F411RE)
|
||||||
// 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
|
// 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
|
HardwareSerial Serial1(PB7, PA15); // Rx=PB7, Tx=PA15 -- CN7 pins 17 and 21 - F411RE
|
||||||
// Serial2 is defined to use USART2 by default, but is in fact used as the diag console
|
// Serial2 is defined to use USART2 by default, but is in fact used as the diag console
|
||||||
@ -67,7 +53,7 @@ HardwareSerial Serial3(PC11, PC10); // Rx=PC11, Tx=PC10 -- USART3 - F446RE
|
|||||||
HardwareSerial Serial5(PD2, PC12); // Rx=PD2, Tx=PC12 -- UART5 - 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
|
// 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) || \
|
#elif defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F446ZE) || \
|
||||||
defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F439ZI) || defined(ARDUINO_NUCLEO_F4X9ZI)
|
defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F439ZI)
|
||||||
// Nucleo-144 boards don't have Serial1 defined by default
|
// Nucleo-144 boards don't have Serial1 defined by default
|
||||||
HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6
|
HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6
|
||||||
HardwareSerial Serial5(PD2, PC12); // Rx=PD2, Tx=PC12 -- UART5
|
HardwareSerial Serial5(PD2, PC12); // Rx=PD2, Tx=PC12 -- UART5
|
||||||
@ -280,23 +266,6 @@ void DCCTimer::reset() {
|
|||||||
while(true) {};
|
while(true) {};
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
|
|
||||||
if (f >= 16)
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f);
|
|
||||||
else if (f == 7)
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 62500);
|
|
||||||
else if (f >= 4)
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 32000);
|
|
||||||
else if (f >= 3)
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 16000);
|
|
||||||
else if (f >= 2)
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 3400);
|
|
||||||
else if (f == 1)
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 480);
|
|
||||||
else
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 131);
|
|
||||||
}
|
|
||||||
|
|
||||||
// TODO: rationalise the size of these... could really use sparse arrays etc.
|
// TODO: rationalise the size of these... could really use sparse arrays etc.
|
||||||
static HardwareTimer * pin_timer[100] = {0};
|
static HardwareTimer * pin_timer[100] = {0};
|
||||||
static uint32_t channel_frequency[100] = {0};
|
static uint32_t channel_frequency[100] = {0};
|
||||||
@ -307,7 +276,7 @@ static uint32_t pin_channel[100] = {0};
|
|||||||
// sophisticated about detecting any clash between the timer we'd like to use for PWM and the ones
|
// sophisticated about detecting any clash between the timer we'd like to use for PWM and the ones
|
||||||
// currently used for HA so they don't interfere with one another. For now we'll just make PWM
|
// currently used for HA so they don't interfere with one another. For now we'll just make PWM
|
||||||
// work well... then work backwards to integrate with HA mode if we can.
|
// work well... then work backwards to integrate with HA mode if we can.
|
||||||
void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency)
|
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency)
|
||||||
{
|
{
|
||||||
if (pin_timer[pin] == NULL) {
|
if (pin_timer[pin] == NULL) {
|
||||||
// Automatically retrieve TIM instance and channel associated to pin
|
// Automatically retrieve TIM instance and channel associated to pin
|
||||||
@ -347,9 +316,7 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value, bool invert) {
|
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
|
||||||
if (invert)
|
|
||||||
value = 255-value;
|
|
||||||
// Calculate percentage duty cycle from value given
|
// Calculate percentage duty cycle from value given
|
||||||
uint32_t duty_cycle = (value * 100 / 256) + 1;
|
uint32_t duty_cycle = (value * 100 / 256) + 1;
|
||||||
if (pin_timer[pin] != NULL) {
|
if (pin_timer[pin] != NULL) {
|
||||||
@ -377,9 +344,9 @@ void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value, bool invert) {
|
|||||||
uint32_t ADCee::usedpins = 0; // Max of 32 ADC input channels!
|
uint32_t ADCee::usedpins = 0; // Max of 32 ADC input channels!
|
||||||
uint8_t ADCee::highestPin = 0; // Highest pin to scan
|
uint8_t ADCee::highestPin = 0; // Highest pin to scan
|
||||||
int * ADCee::analogvals = NULL; // Array of analog values last captured
|
int * ADCee::analogvals = NULL; // Array of analog values last captured
|
||||||
uint32_t * ADCee::analogchans = NULL; // Array of channel numbers to be scanned
|
uint32_t * analogchans = NULL; // Array of channel numbers to be scanned
|
||||||
// bool adc1configured = false;
|
// bool adc1configured = false;
|
||||||
ADC_TypeDef * * ADCee::adcchans = NULL; // Array to capture which ADC is each input channel on
|
ADC_TypeDef * * adcchans = NULL; // Array to capture which ADC is each input channel on
|
||||||
|
|
||||||
int16_t ADCee::ADCmax()
|
int16_t ADCee::ADCmax()
|
||||||
{
|
{
|
||||||
@ -397,10 +364,9 @@ int ADCee::init(uint8_t pin) {
|
|||||||
uint32_t adcchan = STM_PIN_CHANNEL(pinmap_function(stmpin, PinMap_ADC)); // find ADC input channel
|
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.
|
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;
|
int adcnum = 1;
|
||||||
// All variants have ADC1
|
|
||||||
if (adc == ADC1)
|
if (adc == ADC1)
|
||||||
DIAG(F("ADCee::init(): found pin %d on ADC1"), pin);
|
DIAG(F("ADCee::init(): found pin %d on ADC1"), pin);
|
||||||
// Checking for ADC2 and ADC3 being defined helps cater for more variants
|
// Checking for ADC2 and ADC3 being defined helps cater for more variants later
|
||||||
#if defined(ADC2)
|
#if defined(ADC2)
|
||||||
else if (adc == ADC2)
|
else if (adc == ADC2)
|
||||||
{
|
{
|
||||||
@ -447,18 +413,6 @@ int ADCee::init(uint8_t pin) {
|
|||||||
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOFEN; //Power up PORTF
|
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOFEN; //Power up PORTF
|
||||||
gpioBase = GPIOF;
|
gpioBase = GPIOF;
|
||||||
break;
|
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
|
#endif
|
||||||
default:
|
default:
|
||||||
return -1023; // some silly value as error
|
return -1023; // some silly value as error
|
||||||
|
@ -150,11 +150,6 @@ void DCCTimer::reset() {
|
|||||||
SCB_AIRCR = 0x05FA0004;
|
SCB_AIRCR = 0x05FA0004;
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
|
|
||||||
}
|
|
||||||
void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) {
|
|
||||||
}
|
|
||||||
|
|
||||||
int16_t ADCee::ADCmax() {
|
int16_t ADCee::ADCmax() {
|
||||||
return 4095;
|
return 4095;
|
||||||
}
|
}
|
||||||
|
@ -294,7 +294,7 @@ void DCCWaveform::schedulePacket(const byte buffer[], byte byteCount, byte repea
|
|||||||
// The resets will be zero not only now but as well repeats packets into the future
|
// The resets will be zero not only now but as well repeats packets into the future
|
||||||
clearResets(repeats+1);
|
clearResets(repeats+1);
|
||||||
{
|
{
|
||||||
int ret = 0;
|
int ret;
|
||||||
do {
|
do {
|
||||||
if(isMainTrack) {
|
if(isMainTrack) {
|
||||||
if (rmtMainChannel != NULL)
|
if (rmtMainChannel != NULL)
|
||||||
|
218
EXRAIL2.cpp
218
EXRAIL2.cpp
@ -1,5 +1,4 @@
|
|||||||
/*
|
/*
|
||||||
* © 2024 Paul M. Antoine
|
|
||||||
* © 2021 Neil McKechnie
|
* © 2021 Neil McKechnie
|
||||||
* © 2021-2023 Harald Barth
|
* © 2021-2023 Harald Barth
|
||||||
* © 2020-2023 Chris Harlow
|
* © 2020-2023 Chris Harlow
|
||||||
@ -55,7 +54,6 @@
|
|||||||
#include "TrackManager.h"
|
#include "TrackManager.h"
|
||||||
#include "Turntables.h"
|
#include "Turntables.h"
|
||||||
#include "IODevice.h"
|
#include "IODevice.h"
|
||||||
#include "EXRAILSensor.h"
|
|
||||||
|
|
||||||
|
|
||||||
// One instance of RMFT clas is used for each "thread" in the automation.
|
// One instance of RMFT clas is used for each "thread" in the automation.
|
||||||
@ -178,7 +176,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
|
|||||||
|
|
||||||
/* static */ void RMFT2::begin() {
|
/* static */ void RMFT2::begin() {
|
||||||
|
|
||||||
//DIAG(F("EXRAIL RoutCode at =%P"),RouteCode);
|
DIAG(F("EXRAIL RoutCode at =%P"),RouteCode);
|
||||||
|
|
||||||
bool saved_diag=diag;
|
bool saved_diag=diag;
|
||||||
diag=true;
|
diag=true;
|
||||||
@ -206,16 +204,15 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
|
|||||||
|
|
||||||
// Second pass startup, define any turnouts or servos, set signals red
|
// Second pass startup, define any turnouts or servos, set signals red
|
||||||
// add sequences onRoutines to the lookups
|
// add sequences onRoutines to the lookups
|
||||||
if (compileFeatures & FEATURE_SIGNAL) {
|
if (compileFeatures & FEATURE_SIGNAL) {
|
||||||
onRedLookup=LookListLoader(OPCODE_ONRED);
|
onRedLookup=LookListLoader(OPCODE_ONRED);
|
||||||
onAmberLookup=LookListLoader(OPCODE_ONAMBER);
|
onAmberLookup=LookListLoader(OPCODE_ONAMBER);
|
||||||
onGreenLookup=LookListLoader(OPCODE_ONGREEN);
|
onGreenLookup=LookListLoader(OPCODE_ONGREEN);
|
||||||
for (int sigslot=0;;sigslot++) {
|
for (int sigslot=0;;sigslot++) {
|
||||||
int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8);
|
VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8);
|
||||||
if (sighandle==0) break; // end of signal list
|
if (sigid==0) break; // end of signal list
|
||||||
VPIN sigid = sighandle & SIGNAL_ID_MASK;
|
doSignal(sigid & SIGNAL_ID_MASK, SIGNAL_RED);
|
||||||
doSignal(sigid, SIGNAL_RED);
|
}
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int progCounter;
|
int progCounter;
|
||||||
@ -228,6 +225,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
|
|||||||
case OPCODE_AT:
|
case OPCODE_AT:
|
||||||
case OPCODE_ATTIMEOUT2:
|
case OPCODE_ATTIMEOUT2:
|
||||||
case OPCODE_AFTER:
|
case OPCODE_AFTER:
|
||||||
|
case OPCODE_AFTEROVERLOAD:
|
||||||
case OPCODE_IF:
|
case OPCODE_IF:
|
||||||
case OPCODE_IFNOT: {
|
case OPCODE_IFNOT: {
|
||||||
int16_t pin = (int16_t)operand;
|
int16_t pin = (int16_t)operand;
|
||||||
@ -253,14 +251,6 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
|
|||||||
break;
|
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: {
|
case OPCODE_TURNOUT: {
|
||||||
VPIN id=operand;
|
VPIN id=operand;
|
||||||
int addr=getOperand(progCounter,1);
|
int addr=getOperand(progCounter,1);
|
||||||
@ -383,7 +373,7 @@ RMFT2::RMFT2(int progCtr) {
|
|||||||
speedo=0;
|
speedo=0;
|
||||||
forward=true;
|
forward=true;
|
||||||
invert=false;
|
invert=false;
|
||||||
blinkState=not_blink_task;
|
timeoutFlag=false;
|
||||||
stackDepth=0;
|
stackDepth=0;
|
||||||
onEventStartPosition=-1; // Not handling an ONxxx
|
onEventStartPosition=-1; // Not handling an ONxxx
|
||||||
|
|
||||||
@ -421,7 +411,7 @@ void RMFT2::createNewTask(int route, uint16_t cab) {
|
|||||||
|
|
||||||
void RMFT2::driveLoco(byte speed) {
|
void RMFT2::driveLoco(byte speed) {
|
||||||
if (loco<=0) return; // Prevent broadcast!
|
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.....
|
/* TODO.....
|
||||||
power on appropriate track if DC or main if dcc
|
power on appropriate track if DC or main if dcc
|
||||||
if (TrackManager::getMainPowerMode()==POWERMODE::OFF) {
|
if (TrackManager::getMainPowerMode()==POWERMODE::OFF) {
|
||||||
@ -490,8 +480,6 @@ bool RMFT2::skipIfBlock() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void RMFT2::loop() {
|
void RMFT2::loop() {
|
||||||
if (compileFeatures & FEATURE_SENSOR)
|
|
||||||
EXRAILSensor::checkAll();
|
|
||||||
|
|
||||||
// Round Robin call to a RMFT task each time
|
// Round Robin call to a RMFT task each time
|
||||||
if (loopTask==NULL) return;
|
if (loopTask==NULL) return;
|
||||||
@ -503,23 +491,6 @@ void RMFT2::loop() {
|
|||||||
void RMFT2::loop2() {
|
void RMFT2::loop2() {
|
||||||
if (delayTime!=0 && millis()-delayStart < delayTime) return;
|
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;
|
byte opcode = GET_OPCODE;
|
||||||
int16_t operand = getOperand(0);
|
int16_t operand = getOperand(0);
|
||||||
|
|
||||||
@ -540,10 +511,6 @@ void RMFT2::loop2() {
|
|||||||
Turnout::setClosed(operand, true);
|
Turnout::setClosed(operand, true);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OPCODE_TOGGLE_TURNOUT:
|
|
||||||
Turnout::setClosed(operand, Turnout::isThrown(operand));
|
|
||||||
break;
|
|
||||||
|
|
||||||
#ifndef IO_NO_HAL
|
#ifndef IO_NO_HAL
|
||||||
case OPCODE_ROTATE:
|
case OPCODE_ROTATE:
|
||||||
uint8_t activity;
|
uint8_t activity;
|
||||||
@ -593,39 +560,39 @@ void RMFT2::loop2() {
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case OPCODE_AT:
|
case OPCODE_AT:
|
||||||
blinkState=not_blink_task;
|
timeoutFlag=false;
|
||||||
if (readSensor(operand)) break;
|
if (readSensor(operand)) break;
|
||||||
delayMe(50);
|
delayMe(50);
|
||||||
return;
|
return;
|
||||||
|
|
||||||
case OPCODE_ATGTE: // wait for analog sensor>= value
|
case OPCODE_ATGTE: // wait for analog sensor>= value
|
||||||
blinkState=not_blink_task;
|
timeoutFlag=false;
|
||||||
if (IODevice::readAnalogue(operand) >= (int)(getOperand(1))) break;
|
if (IODevice::readAnalogue(operand) >= (int)(getOperand(1))) break;
|
||||||
delayMe(50);
|
delayMe(50);
|
||||||
return;
|
return;
|
||||||
|
|
||||||
case OPCODE_ATLT: // wait for analog sensor < value
|
case OPCODE_ATLT: // wait for analog sensor < value
|
||||||
blinkState=not_blink_task;
|
timeoutFlag=false;
|
||||||
if (IODevice::readAnalogue(operand) < (int)(getOperand(1))) break;
|
if (IODevice::readAnalogue(operand) < (int)(getOperand(1))) break;
|
||||||
delayMe(50);
|
delayMe(50);
|
||||||
return;
|
return;
|
||||||
|
|
||||||
case OPCODE_ATTIMEOUT1: // ATTIMEOUT(vpin,timeout) part 1
|
case OPCODE_ATTIMEOUT1: // ATTIMEOUT(vpin,timeout) part 1
|
||||||
timeoutStart=millis();
|
timeoutStart=millis();
|
||||||
blinkState=not_blink_task;
|
timeoutFlag=false;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OPCODE_ATTIMEOUT2:
|
case OPCODE_ATTIMEOUT2:
|
||||||
if (readSensor(operand)) break; // success without timeout
|
if (readSensor(operand)) break; // success without timeout
|
||||||
if (millis()-timeoutStart > 100*getOperand(1)) {
|
if (millis()-timeoutStart > 100*getOperand(1)) {
|
||||||
blinkState=at_timeout;
|
timeoutFlag=true;
|
||||||
break; // and drop through
|
break; // and drop through
|
||||||
}
|
}
|
||||||
delayMe(50);
|
delayMe(50);
|
||||||
return;
|
return;
|
||||||
|
|
||||||
case OPCODE_IFTIMEOUT: // do next operand if timeout flag set
|
case OPCODE_IFTIMEOUT: // do next operand if timeout flag set
|
||||||
skipIf=blinkState!=at_timeout;
|
skipIf=!timeoutFlag;
|
||||||
break;
|
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 0.5 seconds. (must come after an AT operation)
|
||||||
@ -657,25 +624,13 @@ void RMFT2::loop2() {
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case OPCODE_SET:
|
case OPCODE_SET:
|
||||||
killBlinkOnVpin(operand);
|
|
||||||
IODevice::write(operand,true);
|
IODevice::write(operand,true);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OPCODE_RESET:
|
case OPCODE_RESET:
|
||||||
killBlinkOnVpin(operand);
|
|
||||||
IODevice::write(operand,false);
|
IODevice::write(operand,false);
|
||||||
break;
|
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:
|
case OPCODE_PAUSE:
|
||||||
DCC::setThrottle(0,1,true); // pause all locos on the track
|
DCC::setThrottle(0,1,true); // pause all locos on the track
|
||||||
pausingTask=this;
|
pausingTask=this;
|
||||||
@ -714,45 +669,6 @@ void RMFT2::loop2() {
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
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;
|
|
||||||
}
|
|
||||||
|
|
||||||
break;
|
|
||||||
|
|
||||||
case OPCODE_RESUME:
|
case OPCODE_RESUME:
|
||||||
pausingTask=NULL;
|
pausingTask=NULL;
|
||||||
driveLoco(speedo);
|
driveLoco(speedo);
|
||||||
@ -861,10 +777,6 @@ void RMFT2::loop2() {
|
|||||||
if (loco) DCC::setFn(loco,operand,false);
|
if (loco) DCC::setFn(loco,operand,false);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OPCODE_FTOGGLE:
|
|
||||||
if (loco) DCC::changeFn(loco,operand);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case OPCODE_DRIVE:
|
case OPCODE_DRIVE:
|
||||||
{
|
{
|
||||||
byte analogSpeed=IODevice::readAnalogue(operand) *127 / 1024;
|
byte analogSpeed=IODevice::readAnalogue(operand) *127 / 1024;
|
||||||
@ -880,10 +792,6 @@ void RMFT2::loop2() {
|
|||||||
DCC::setFn(operand,getOperand(1),false);
|
DCC::setFn(operand,getOperand(1),false);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OPCODE_XFTOGGLE:
|
|
||||||
DCC::changeFn(operand,getOperand(1));
|
|
||||||
break;
|
|
||||||
|
|
||||||
case OPCODE_DCCACTIVATE: {
|
case OPCODE_DCCACTIVATE: {
|
||||||
// operand is address<<3 | subaddr<<1 | active
|
// operand is address<<3 | subaddr<<1 | active
|
||||||
int16_t addr=operand>>3;
|
int16_t addr=operand>>3;
|
||||||
@ -1001,14 +909,6 @@ void RMFT2::loop2() {
|
|||||||
StringFormatter::send(LCCSerial,F("<L x%h>"),(uint16_t)operand);
|
StringFormatter::send(LCCSerial,F("<L x%h>"),(uint16_t)operand);
|
||||||
break;
|
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
|
case OPCODE_LCCX: // long form LCC
|
||||||
if ((compileFeatures & FEATURE_LCC) && LCCSerial)
|
if ((compileFeatures & FEATURE_LCC) && LCCSerial)
|
||||||
StringFormatter::send(LCCSerial,F("<L x%h%h%h%h>\n"),
|
StringFormatter::send(LCCSerial,F("<L x%h%h%h%h>\n"),
|
||||||
@ -1086,7 +986,7 @@ void RMFT2::loop2() {
|
|||||||
case OPCODE_ROUTE:
|
case OPCODE_ROUTE:
|
||||||
case OPCODE_AUTOMATION:
|
case OPCODE_AUTOMATION:
|
||||||
case OPCODE_SEQUENCE:
|
case OPCODE_SEQUENCE:
|
||||||
//if (diag) DIAG(F("EXRAIL begin(%d)"),operand);
|
if (diag) DIAG(F("EXRAIL begin(%d)"),operand);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OPCODE_AUTOSTART: // Handled only during begin process
|
case OPCODE_AUTOSTART: // Handled only during begin process
|
||||||
@ -1096,8 +996,6 @@ void RMFT2::loop2() {
|
|||||||
case OPCODE_PINTURNOUT: // Turnout definition ignored at runtime
|
case OPCODE_PINTURNOUT: // Turnout definition ignored at runtime
|
||||||
case OPCODE_ONCLOSE: // Turnout event catchers ignored here
|
case OPCODE_ONCLOSE: // Turnout event catchers ignored here
|
||||||
case OPCODE_ONLCC: // LCC 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_ONTHROW:
|
||||||
case OPCODE_ONACTIVATE: // Activate event catchers ignored here
|
case OPCODE_ONACTIVATE: // Activate event catchers ignored here
|
||||||
case OPCODE_ONDEACTIVATE:
|
case OPCODE_ONDEACTIVATE:
|
||||||
@ -1106,8 +1004,6 @@ void RMFT2::loop2() {
|
|||||||
case OPCODE_ONGREEN:
|
case OPCODE_ONGREEN:
|
||||||
case OPCODE_ONCHANGE:
|
case OPCODE_ONCHANGE:
|
||||||
case OPCODE_ONTIME:
|
case OPCODE_ONTIME:
|
||||||
case OPCODE_ONBUTTON:
|
|
||||||
case OPCODE_ONSENSOR:
|
|
||||||
#ifndef IO_NO_HAL
|
#ifndef IO_NO_HAL
|
||||||
case OPCODE_DCCTURNTABLE: // Turntable definition ignored at runtime
|
case OPCODE_DCCTURNTABLE: // Turntable definition ignored at runtime
|
||||||
case OPCODE_EXTTTURNTABLE: // Turntable definition ignored at runtime
|
case OPCODE_EXTTTURNTABLE: // Turntable definition ignored at runtime
|
||||||
@ -1153,30 +1049,24 @@ void RMFT2::kill(const FSH * reason, int operand) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
int16_t RMFT2::getSignalSlot(int16_t id) {
|
int16_t RMFT2::getSignalSlot(int16_t id) {
|
||||||
|
for (int sigslot=0;;sigslot++) {
|
||||||
if (id > 0) {
|
int16_t sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8);
|
||||||
int sigslot = 0;
|
if (sigid==0) { // end of signal list
|
||||||
int16_t sighandle = 0;
|
DIAG(F("EXRAIL Signal %d not defined"), id);
|
||||||
// Trundle down the signal list until we reach the end
|
return -1;
|
||||||
while ((sighandle = GETHIGHFLASHW(RMFT2::SignalDefinitions, sigslot * 8)) != 0)
|
}
|
||||||
{
|
|
||||||
// sigid is the signal id used in RED/AMBER/GREEN macro
|
// sigid is the signal id used in RED/AMBER/GREEN macro
|
||||||
// for a LED signal it will be same as redpin
|
// for a LED signal it will be same as redpin
|
||||||
// but for a servo signal it will also have SERVO_SIGNAL_FLAG set.
|
// 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
|
if ((sigid & SIGNAL_ID_MASK)!= id) continue; // keep looking
|
||||||
return sigslot; // found it
|
return sigslot; // relative slot in signals table
|
||||||
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) {
|
/* static */ void RMFT2::doSignal(int16_t id,char rag) {
|
||||||
if (!(compileFeatures & FEATURE_SIGNAL)) return; // dont compile code below
|
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.
|
// Schedule any event handler for this signal change.
|
||||||
// This will work even without a signal definition.
|
// This will work even without a signal definition.
|
||||||
@ -1192,20 +1082,19 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
|
|||||||
|
|
||||||
// Correct signal definition found, get the rag values
|
// Correct signal definition found, get the rag values
|
||||||
int16_t sigpos=sigslot*8;
|
int16_t sigpos=sigslot*8;
|
||||||
int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos);
|
VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos);
|
||||||
VPIN redpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+2);
|
VPIN redpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+2);
|
||||||
VPIN amberpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+4);
|
VPIN amberpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+4);
|
||||||
VPIN greenpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+6);
|
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=sighandle & ~SIGNAL_ID_MASK;
|
VPIN sigtype=sigid & ~SIGNAL_ID_MASK;
|
||||||
VPIN sigid = sighandle & SIGNAL_ID_MASK;
|
|
||||||
|
|
||||||
if (sigtype == SERVO_SIGNAL_FLAG) {
|
if (sigtype == SERVO_SIGNAL_FLAG) {
|
||||||
// A servo signal, the pin numbers are actually servo positions
|
// A servo signal, the pin numbers are actually servo positions
|
||||||
// Note, setting a signal to a zero position has no effect.
|
// Note, setting a signal to a zero position has no effect.
|
||||||
int16_t servopos= rag==SIGNAL_RED? redpin: (rag==SIGNAL_GREEN? greenpin : amberpin);
|
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);
|
if (servopos!=0) IODevice::writeAnalogue(id,servopos,PCA9685::Bounce);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -1222,7 +1111,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
|
|||||||
byte value=redpin;
|
byte value=redpin;
|
||||||
if (rag==SIGNAL_AMBER) value=amberpin;
|
if (rag==SIGNAL_AMBER) value=amberpin;
|
||||||
if (rag==SIGNAL_GREEN) value=greenpin;
|
if (rag==SIGNAL_GREEN) value=greenpin;
|
||||||
DCC::setExtendedAccessory(sigid, value);
|
DCC::setExtendedAccessory(sigid & SIGNAL_ID_MASK,value);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1233,25 +1122,22 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
|
|||||||
if (rag==SIGNAL_AMBER && (amberpin==0)) rag=SIMAMBER; // special case this func only
|
if (rag==SIGNAL_AMBER && (amberpin==0)) rag=SIMAMBER; // special case this func only
|
||||||
|
|
||||||
// Manage invert (HIGH on) pins
|
// Manage invert (HIGH on) pins
|
||||||
bool aHigh=sighandle & ACTIVE_HIGH_SIGNAL_FLAG;
|
bool aHigh=sigid & ACTIVE_HIGH_SIGNAL_FLAG;
|
||||||
|
|
||||||
// set the three pins
|
// set the three pins
|
||||||
if (redpin) {
|
if (redpin) {
|
||||||
bool redval=(rag==SIGNAL_RED || rag==SIMAMBER);
|
bool redval=(rag==SIGNAL_RED || rag==SIMAMBER);
|
||||||
if (!aHigh) redval=!redval;
|
if (!aHigh) redval=!redval;
|
||||||
killBlinkOnVpin(redpin);
|
|
||||||
IODevice::write(redpin,redval);
|
IODevice::write(redpin,redval);
|
||||||
}
|
}
|
||||||
if (amberpin) {
|
if (amberpin) {
|
||||||
bool amberval=(rag==SIGNAL_AMBER);
|
bool amberval=(rag==SIGNAL_AMBER);
|
||||||
if (!aHigh) amberval=!amberval;
|
if (!aHigh) amberval=!amberval;
|
||||||
killBlinkOnVpin(amberpin);
|
|
||||||
IODevice::write(amberpin,amberval);
|
IODevice::write(amberpin,amberval);
|
||||||
}
|
}
|
||||||
if (greenpin) {
|
if (greenpin) {
|
||||||
bool greenval=(rag==SIGNAL_GREEN || rag==SIMAMBER);
|
bool greenval=(rag==SIGNAL_GREEN || rag==SIMAMBER);
|
||||||
if (!aHigh) greenval=!greenval;
|
if (!aHigh) greenval=!greenval;
|
||||||
killBlinkOnVpin(greenpin);
|
|
||||||
IODevice::write(greenpin,greenval);
|
IODevice::write(greenpin,greenval);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -1273,9 +1159,8 @@ bool RMFT2::signalAspectEvent(int16_t address, byte aspect ) {
|
|||||||
int16_t sigslot=getSignalSlot(address);
|
int16_t sigslot=getSignalSlot(address);
|
||||||
if (sigslot<0) return false; // this is not a defined signal
|
if (sigslot<0) return false; // this is not a defined signal
|
||||||
int16_t sigpos=sigslot*8;
|
int16_t sigpos=sigslot*8;
|
||||||
int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos);
|
VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos);
|
||||||
VPIN sigtype=sighandle & ~SIGNAL_ID_MASK;
|
VPIN sigtype=sigid & ~SIGNAL_ID_MASK;
|
||||||
VPIN sigid = sighandle & SIGNAL_ID_MASK;
|
|
||||||
if (sigtype!=DCCX_SIGNAL_FLAG) return false; // not a DCCX signal
|
if (sigtype!=DCCX_SIGNAL_FLAG) return false; // not a DCCX signal
|
||||||
// Turn an aspect change into a RED/AMBER/GREEN setting
|
// Turn an aspect change into a RED/AMBER/GREEN setting
|
||||||
if (aspect==GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+2)) {
|
if (aspect==GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+2)) {
|
||||||
@ -1324,7 +1209,7 @@ void RMFT2::rotateEvent(int16_t turntableId, bool change) {
|
|||||||
void RMFT2::clockEvent(int16_t clocktime, bool change) {
|
void RMFT2::clockEvent(int16_t clocktime, bool change) {
|
||||||
// Hunt for an ONTIME for this time
|
// Hunt for an ONTIME for this time
|
||||||
if (Diag::CMD)
|
if (Diag::CMD)
|
||||||
DIAG(F("clockEvent at : %d"), clocktime);
|
DIAG(F("Looking for clock event at : %d"), clocktime);
|
||||||
if (change) {
|
if (change) {
|
||||||
onClockLookup->handleEvent(F("CLOCK"),clocktime);
|
onClockLookup->handleEvent(F("CLOCK"),clocktime);
|
||||||
onClockLookup->handleEvent(F("CLOCK"),25*60+clocktime%60);
|
onClockLookup->handleEvent(F("CLOCK"),25*60+clocktime%60);
|
||||||
@ -1334,31 +1219,12 @@ void RMFT2::clockEvent(int16_t clocktime, bool change) {
|
|||||||
void RMFT2::powerEvent(int16_t track, bool overload) {
|
void RMFT2::powerEvent(int16_t track, bool overload) {
|
||||||
// Hunt for an ONOVERLOAD for this item
|
// Hunt for an ONOVERLOAD for this item
|
||||||
if (Diag::CMD)
|
if (Diag::CMD)
|
||||||
DIAG(F("powerEvent : %c"), track);
|
DIAG(F("Looking for Power event on track : %c"), track);
|
||||||
if (overload) {
|
if (overload) {
|
||||||
onOverloadLookup->handleEvent(F("POWER"),track);
|
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) {
|
void RMFT2::startNonRecursiveTask(const FSH* reason, int16_t id,int pc) {
|
||||||
// Check we dont already have a task running this handler
|
// Check we dont already have a task running this handler
|
||||||
RMFT2 * task=loopTask;
|
RMFT2 * task=loopTask;
|
||||||
@ -1429,7 +1295,6 @@ void RMFT2::thrungeString(uint32_t strfar, thrunger mode, byte id) {
|
|||||||
break;
|
break;
|
||||||
case thrunge_parse:
|
case thrunge_parse:
|
||||||
case thrunge_broadcast:
|
case thrunge_broadcast:
|
||||||
case thrunge_message:
|
|
||||||
case thrunge_lcd:
|
case thrunge_lcd:
|
||||||
default: // thrunge_lcd+1, ...
|
default: // thrunge_lcd+1, ...
|
||||||
if (!buffer) buffer=new StringBuffer();
|
if (!buffer) buffer=new StringBuffer();
|
||||||
@ -1467,9 +1332,6 @@ void RMFT2::thrungeString(uint32_t strfar, thrunger mode, byte id) {
|
|||||||
case thrunge_withrottle:
|
case thrunge_withrottle:
|
||||||
CommandDistributor::broadcastRaw(CommandDistributor::WITHROTTLE_TYPE,buffer->getString());
|
CommandDistributor::broadcastRaw(CommandDistributor::WITHROTTLE_TYPE,buffer->getString());
|
||||||
break;
|
break;
|
||||||
case thrunge_message:
|
|
||||||
CommandDistributor::broadcastMessage(buffer->getString());
|
|
||||||
break;
|
|
||||||
case thrunge_lcd:
|
case thrunge_lcd:
|
||||||
LCD(id,F("%s"),buffer->getString());
|
LCD(id,F("%s"),buffer->getString());
|
||||||
break;
|
break;
|
||||||
|
31
EXRAIL2.h
31
EXRAIL2.h
@ -33,7 +33,7 @@
|
|||||||
// or more OPCODE_PAD instructions with the subsequent parameters. This wastes a byte but makes
|
// 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.
|
// searching easier as a parameter can never be confused with an opcode.
|
||||||
//
|
//
|
||||||
enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,OPCODE_TOGGLE_TURNOUT,
|
enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,
|
||||||
OPCODE_FWD,OPCODE_REV,OPCODE_SPEED,OPCODE_INVERT_DIRECTION,
|
OPCODE_FWD,OPCODE_REV,OPCODE_SPEED,OPCODE_INVERT_DIRECTION,
|
||||||
OPCODE_RESERVE,OPCODE_FREE,
|
OPCODE_RESERVE,OPCODE_FREE,
|
||||||
OPCODE_AT,OPCODE_AFTER,
|
OPCODE_AT,OPCODE_AFTER,
|
||||||
@ -41,11 +41,9 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,OPCODE_TOGGLE_TURNOUT,
|
|||||||
OPCODE_ATGTE,OPCODE_ATLT,
|
OPCODE_ATGTE,OPCODE_ATLT,
|
||||||
OPCODE_ATTIMEOUT1,OPCODE_ATTIMEOUT2,
|
OPCODE_ATTIMEOUT1,OPCODE_ATTIMEOUT2,
|
||||||
OPCODE_LATCH,OPCODE_UNLATCH,OPCODE_SET,OPCODE_RESET,
|
OPCODE_LATCH,OPCODE_UNLATCH,OPCODE_SET,OPCODE_RESET,
|
||||||
OPCODE_BLINK,
|
|
||||||
OPCODE_ENDIF,OPCODE_ELSE,
|
OPCODE_ENDIF,OPCODE_ELSE,
|
||||||
OPCODE_DELAY,OPCODE_DELAYMINS,OPCODE_DELAYMS,OPCODE_RANDWAIT,
|
OPCODE_DELAY,OPCODE_DELAYMINS,OPCODE_DELAYMS,OPCODE_RANDWAIT,
|
||||||
OPCODE_FON,OPCODE_FOFF,OPCODE_XFON,OPCODE_XFOFF,
|
OPCODE_FON,OPCODE_FOFF,OPCODE_XFON,OPCODE_XFOFF,
|
||||||
OPCODE_FTOGGLE,OPCODE_XFTOGGLE,
|
|
||||||
OPCODE_RED,OPCODE_GREEN,OPCODE_AMBER,OPCODE_DRIVE,
|
OPCODE_RED,OPCODE_GREEN,OPCODE_AMBER,OPCODE_DRIVE,
|
||||||
OPCODE_SERVO,OPCODE_SIGNAL,OPCODE_TURNOUT,OPCODE_WAITFOR,
|
OPCODE_SERVO,OPCODE_SIGNAL,OPCODE_TURNOUT,OPCODE_WAITFOR,
|
||||||
OPCODE_PAD,OPCODE_FOLLOW,OPCODE_CALL,OPCODE_RETURN,
|
OPCODE_PAD,OPCODE_FOLLOW,OPCODE_CALL,OPCODE_RETURN,
|
||||||
@ -53,7 +51,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,OPCODE_TOGGLE_TURNOUT,
|
|||||||
OPCODE_JOIN,OPCODE_UNJOIN,OPCODE_READ_LOCO1,OPCODE_READ_LOCO2,
|
OPCODE_JOIN,OPCODE_UNJOIN,OPCODE_READ_LOCO1,OPCODE_READ_LOCO2,
|
||||||
#endif
|
#endif
|
||||||
OPCODE_POM,
|
OPCODE_POM,
|
||||||
OPCODE_START,OPCODE_SETLOCO,OPCODE_SETFREQ,OPCODE_SENDLOCO,OPCODE_FORGET,
|
OPCODE_START,OPCODE_SETLOCO,OPCODE_SENDLOCO,OPCODE_FORGET,
|
||||||
OPCODE_PAUSE, OPCODE_RESUME,OPCODE_POWEROFF,OPCODE_POWERON,
|
OPCODE_PAUSE, OPCODE_RESUME,OPCODE_POWEROFF,OPCODE_POWERON,
|
||||||
OPCODE_ONCLOSE, OPCODE_ONTHROW, OPCODE_SERVOTURNOUT, OPCODE_PINTURNOUT,
|
OPCODE_ONCLOSE, OPCODE_ONTHROW, OPCODE_SERVOTURNOUT, OPCODE_PINTURNOUT,
|
||||||
OPCODE_PRINT,OPCODE_DCCACTIVATE,OPCODE_ASPECT,
|
OPCODE_PRINT,OPCODE_DCCACTIVATE,OPCODE_ASPECT,
|
||||||
@ -69,13 +67,11 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,OPCODE_TOGGLE_TURNOUT,
|
|||||||
OPCODE_TTADDPOSITION,OPCODE_DCCTURNTABLE,OPCODE_EXTTTURNTABLE,
|
OPCODE_TTADDPOSITION,OPCODE_DCCTURNTABLE,OPCODE_EXTTTURNTABLE,
|
||||||
OPCODE_ONROTATE,OPCODE_ROTATE,OPCODE_WAITFORTT,
|
OPCODE_ONROTATE,OPCODE_ROTATE,OPCODE_WAITFORTT,
|
||||||
OPCODE_LCC,OPCODE_LCCX,OPCODE_ONLCC,
|
OPCODE_LCC,OPCODE_LCCX,OPCODE_ONLCC,
|
||||||
OPCODE_ACON, OPCODE_ACOF,
|
|
||||||
OPCODE_ONACON, OPCODE_ONACOF,
|
|
||||||
OPCODE_ONOVERLOAD,
|
OPCODE_ONOVERLOAD,
|
||||||
OPCODE_ROUTE_ACTIVE,OPCODE_ROUTE_INACTIVE,OPCODE_ROUTE_HIDDEN,
|
OPCODE_ROUTE_ACTIVE,OPCODE_ROUTE_INACTIVE,OPCODE_ROUTE_HIDDEN,
|
||||||
OPCODE_ROUTE_DISABLED,
|
OPCODE_ROUTE_DISABLED,
|
||||||
OPCODE_STASH,OPCODE_CLEAR_STASH,OPCODE_CLEAR_ALL_STASH,OPCODE_PICKUP_STASH,
|
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
|
// OPcodes below this point are skip-nesting IF operations
|
||||||
// placed here so that they may be skipped as a group
|
// placed here so that they may be skipped as a group
|
||||||
// see skipIfBlock()
|
// see skipIfBlock()
|
||||||
@ -98,26 +94,16 @@ enum thrunger: byte {
|
|||||||
thrunge_serial,thrunge_parse,
|
thrunge_serial,thrunge_parse,
|
||||||
thrunge_serial1, thrunge_serial2, thrunge_serial3,
|
thrunge_serial1, thrunge_serial2, thrunge_serial3,
|
||||||
thrunge_serial4, thrunge_serial5, thrunge_serial6,
|
thrunge_serial4, thrunge_serial5, thrunge_serial6,
|
||||||
thrunge_lcn,thrunge_message,
|
thrunge_lcn,
|
||||||
thrunge_lcd, // Must be last!!
|
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.
|
// Flag bits for compile time features.
|
||||||
static const byte FEATURE_SIGNAL= 0x80;
|
static const byte FEATURE_SIGNAL= 0x80;
|
||||||
static const byte FEATURE_LCC = 0x40;
|
static const byte FEATURE_LCC = 0x40;
|
||||||
static const byte FEATURE_ROSTER= 0x20;
|
static const byte FEATURE_ROSTER= 0x20;
|
||||||
static const byte FEATURE_ROUTESTATE= 0x10;
|
static const byte FEATURE_ROUTESTATE= 0x10;
|
||||||
static const byte FEATURE_STASH = 0x08;
|
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
|
// Flag bits for status of hardware and TPL
|
||||||
@ -188,8 +174,6 @@ class LookList {
|
|||||||
static const FSH * getTurntableDescription(int16_t id);
|
static const FSH * getTurntableDescription(int16_t id);
|
||||||
static const FSH * getTurntablePositionDescription(int16_t turntableId, uint8_t positionId);
|
static const FSH * getTurntablePositionDescription(int16_t turntableId, uint8_t positionId);
|
||||||
static void startNonRecursiveTask(const FSH* reason, int16_t id,int pc);
|
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:
|
private:
|
||||||
static void ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]);
|
static void ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]);
|
||||||
@ -199,6 +183,7 @@ private:
|
|||||||
static bool getFlag(VPIN id,byte mask);
|
static bool getFlag(VPIN id,byte mask);
|
||||||
static int16_t progtrackLocoId;
|
static int16_t progtrackLocoId;
|
||||||
static void doSignal(int16_t id,char rag);
|
static void doSignal(int16_t id,char rag);
|
||||||
|
static bool isSignal(int16_t id,char rag);
|
||||||
static int16_t getSignalSlot(int16_t id);
|
static int16_t getSignalSlot(int16_t id);
|
||||||
static void setTurnoutHiddenState(Turnout * t);
|
static void setTurnoutHiddenState(Turnout * t);
|
||||||
#ifndef IO_NO_HAL
|
#ifndef IO_NO_HAL
|
||||||
@ -207,11 +192,11 @@ private:
|
|||||||
static LookList* LookListLoader(OPCODE op1,
|
static LookList* LookListLoader(OPCODE op1,
|
||||||
OPCODE op2=OPCODE_ENDEXRAIL,OPCODE op3=OPCODE_ENDEXRAIL);
|
OPCODE op2=OPCODE_ENDEXRAIL,OPCODE op3=OPCODE_ENDEXRAIL);
|
||||||
static uint16_t getOperand(int progCounter,byte n);
|
static uint16_t getOperand(int progCounter,byte n);
|
||||||
static void killBlinkOnVpin(VPIN pin);
|
|
||||||
static RMFT2 * loopTask;
|
static RMFT2 * loopTask;
|
||||||
static RMFT2 * pausingTask;
|
static RMFT2 * pausingTask;
|
||||||
void delayMe(long millisecs);
|
void delayMe(long millisecs);
|
||||||
void driveLoco(byte speedo);
|
void driveLoco(byte speedo);
|
||||||
|
bool readSensor(uint16_t sensorId);
|
||||||
bool skipIfBlock();
|
bool skipIfBlock();
|
||||||
bool readLoco();
|
bool readLoco();
|
||||||
void loop2();
|
void loop2();
|
||||||
@ -259,10 +244,10 @@ private:
|
|||||||
union {
|
union {
|
||||||
unsigned long waitAfter; // Used by OPCODE_AFTER
|
unsigned long waitAfter; // Used by OPCODE_AFTER
|
||||||
unsigned long timeoutStart; // Used by OPCODE_ATTIMEOUT
|
unsigned long timeoutStart; // Used by OPCODE_ATTIMEOUT
|
||||||
VPIN blinkPin; // Used by blink tasks
|
|
||||||
};
|
};
|
||||||
|
bool timeoutFlag;
|
||||||
byte taskId;
|
byte taskId;
|
||||||
BlinkState blinkState; // includes AT_TIMEOUT flag.
|
|
||||||
uint16_t loco;
|
uint16_t loco;
|
||||||
bool forward;
|
bool forward;
|
||||||
bool invert;
|
bool invert;
|
||||||
|
@ -38,7 +38,6 @@
|
|||||||
#undef ATTIMEOUT
|
#undef ATTIMEOUT
|
||||||
#undef AUTOMATION
|
#undef AUTOMATION
|
||||||
#undef AUTOSTART
|
#undef AUTOSTART
|
||||||
#undef BLINK
|
|
||||||
#undef BROADCAST
|
#undef BROADCAST
|
||||||
#undef CALL
|
#undef CALL
|
||||||
#undef CLEAR_STASH
|
#undef CLEAR_STASH
|
||||||
@ -67,7 +66,6 @@
|
|||||||
#undef FOLLOW
|
#undef FOLLOW
|
||||||
#undef FON
|
#undef FON
|
||||||
#undef FORGET
|
#undef FORGET
|
||||||
#undef FTOGGLE
|
|
||||||
#undef FREE
|
#undef FREE
|
||||||
#undef FWD
|
#undef FWD
|
||||||
#undef GREEN
|
#undef GREEN
|
||||||
@ -99,11 +97,6 @@
|
|||||||
#undef LCCX
|
#undef LCCX
|
||||||
#undef LCN
|
#undef LCN
|
||||||
#undef MOVETT
|
#undef MOVETT
|
||||||
#undef ACON
|
|
||||||
#undef ACOF
|
|
||||||
#undef ONACON
|
|
||||||
#undef ONACOF
|
|
||||||
#undef MESSAGE
|
|
||||||
#undef ONACTIVATE
|
#undef ONACTIVATE
|
||||||
#undef ONACTIVATEL
|
#undef ONACTIVATEL
|
||||||
#undef ONAMBER
|
#undef ONAMBER
|
||||||
@ -118,8 +111,6 @@
|
|||||||
#undef ONGREEN
|
#undef ONGREEN
|
||||||
#undef ONRED
|
#undef ONRED
|
||||||
#undef ONROTATE
|
#undef ONROTATE
|
||||||
#undef ONBUTTON
|
|
||||||
#undef ONSENSOR
|
|
||||||
#undef ONTHROW
|
#undef ONTHROW
|
||||||
#undef ONCHANGE
|
#undef ONCHANGE
|
||||||
#undef PARSE
|
#undef PARSE
|
||||||
@ -165,17 +156,14 @@
|
|||||||
#undef SET_TRACK
|
#undef SET_TRACK
|
||||||
#undef SET_POWER
|
#undef SET_POWER
|
||||||
#undef SETLOCO
|
#undef SETLOCO
|
||||||
#undef SETFREQ
|
|
||||||
#undef SIGNAL
|
#undef SIGNAL
|
||||||
#undef SIGNALH
|
#undef SIGNALH
|
||||||
#undef SPEED
|
#undef SPEED
|
||||||
#undef START
|
#undef START
|
||||||
#undef STASH
|
#undef STASH
|
||||||
#undef STEALTH
|
#undef STEALTH
|
||||||
#undef STEALTH_GLOBAL
|
|
||||||
#undef STOP
|
#undef STOP
|
||||||
#undef THROW
|
#undef THROW
|
||||||
#undef TOGGLE_TURNOUT
|
|
||||||
#undef TT_ADDPOSITION
|
#undef TT_ADDPOSITION
|
||||||
#undef TURNOUT
|
#undef TURNOUT
|
||||||
#undef TURNOUTL
|
#undef TURNOUTL
|
||||||
@ -190,7 +178,6 @@
|
|||||||
#undef WITHROTTLE
|
#undef WITHROTTLE
|
||||||
#undef XFOFF
|
#undef XFOFF
|
||||||
#undef XFON
|
#undef XFON
|
||||||
#undef XFTOGGLE
|
|
||||||
|
|
||||||
#ifndef RMFT2_UNDEF_ONLY
|
#ifndef RMFT2_UNDEF_ONLY
|
||||||
#define ACTIVATE(addr,subaddr)
|
#define ACTIVATE(addr,subaddr)
|
||||||
@ -207,7 +194,6 @@
|
|||||||
#define ATTIMEOUT(sensor_id,timeout_ms)
|
#define ATTIMEOUT(sensor_id,timeout_ms)
|
||||||
#define AUTOMATION(id,description)
|
#define AUTOMATION(id,description)
|
||||||
#define AUTOSTART
|
#define AUTOSTART
|
||||||
#define BLINK(vpin,onDuty,offDuty)
|
|
||||||
#define BROADCAST(msg)
|
#define BROADCAST(msg)
|
||||||
#define CALL(route)
|
#define CALL(route)
|
||||||
#define CLEAR_STASH(id)
|
#define CLEAR_STASH(id)
|
||||||
@ -237,7 +223,6 @@
|
|||||||
#define FON(func)
|
#define FON(func)
|
||||||
#define FORGET
|
#define FORGET
|
||||||
#define FREE(blockid)
|
#define FREE(blockid)
|
||||||
#define FTOGGLE(func)
|
|
||||||
#define FWD(speed)
|
#define FWD(speed)
|
||||||
#define GREEN(signal_id)
|
#define GREEN(signal_id)
|
||||||
#define HAL(haltype,params...)
|
#define HAL(haltype,params...)
|
||||||
@ -267,12 +252,7 @@
|
|||||||
#define LCD(row,msg)
|
#define LCD(row,msg)
|
||||||
#define SCREEN(display,row,msg)
|
#define SCREEN(display,row,msg)
|
||||||
#define LCN(msg)
|
#define LCN(msg)
|
||||||
#define MESSAGE(msg)
|
|
||||||
#define MOVETT(id,steps,activity)
|
#define MOVETT(id,steps,activity)
|
||||||
#define ACON(eventid)
|
|
||||||
#define ACOF(eventid)
|
|
||||||
#define ONACON(eventid)
|
|
||||||
#define ONACOF(eventid)
|
|
||||||
#define ONACTIVATE(addr,subaddr)
|
#define ONACTIVATE(addr,subaddr)
|
||||||
#define ONACTIVATEL(linear)
|
#define ONACTIVATEL(linear)
|
||||||
#define ONAMBER(signal_id)
|
#define ONAMBER(signal_id)
|
||||||
@ -289,8 +269,6 @@
|
|||||||
#define ONROTATE(turntable_id)
|
#define ONROTATE(turntable_id)
|
||||||
#define ONTHROW(turnout_id)
|
#define ONTHROW(turnout_id)
|
||||||
#define ONCHANGE(sensor_id)
|
#define ONCHANGE(sensor_id)
|
||||||
#define ONSENSOR(sensor_id)
|
|
||||||
#define ONBUTTON(sensor_id)
|
|
||||||
#define PAUSE
|
#define PAUSE
|
||||||
#define PIN_TURNOUT(id,pin,description...)
|
#define PIN_TURNOUT(id,pin,description...)
|
||||||
#define PRINT(msg)
|
#define PRINT(msg)
|
||||||
@ -334,17 +312,14 @@
|
|||||||
#define SET_TRACK(track,mode)
|
#define SET_TRACK(track,mode)
|
||||||
#define SET_POWER(track,onoff)
|
#define SET_POWER(track,onoff)
|
||||||
#define SETLOCO(loco)
|
#define SETLOCO(loco)
|
||||||
#define SETFREQ(loco,freq)
|
|
||||||
#define SIGNAL(redpin,amberpin,greenpin)
|
#define SIGNAL(redpin,amberpin,greenpin)
|
||||||
#define SIGNALH(redpin,amberpin,greenpin)
|
#define SIGNALH(redpin,amberpin,greenpin)
|
||||||
#define SPEED(speed)
|
#define SPEED(speed)
|
||||||
#define START(route)
|
#define START(route)
|
||||||
#define STASH(id)
|
#define STASH(id)
|
||||||
#define STEALTH(code...)
|
#define STEALTH(code...)
|
||||||
#define STEALTH_GLOBAL(code...)
|
|
||||||
#define STOP
|
#define STOP
|
||||||
#define THROW(id)
|
#define THROW(id)
|
||||||
#define TOGGLE_TURNOUT(id)
|
|
||||||
#define TT_ADDPOSITION(turntable_id,position,value,angle,description...)
|
#define TT_ADDPOSITION(turntable_id,position,value,angle,description...)
|
||||||
#define TURNOUT(id,addr,subaddr,description...)
|
#define TURNOUT(id,addr,subaddr,description...)
|
||||||
#define TURNOUTL(id,addr,description...)
|
#define TURNOUTL(id,addr,description...)
|
||||||
@ -359,6 +334,4 @@
|
|||||||
#define WITHROTTLE(msg)
|
#define WITHROTTLE(msg)
|
||||||
#define XFOFF(cab,func)
|
#define XFOFF(cab,func)
|
||||||
#define XFON(cab,func)
|
#define XFON(cab,func)
|
||||||
#define XFTOGGLE(cab,func)
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -36,7 +36,7 @@
|
|||||||
|
|
||||||
void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]) {
|
void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]) {
|
||||||
(void)stream; // avoid compiler warning if we don't access this parameter
|
(void)stream; // avoid compiler warning if we don't access this parameter
|
||||||
|
bool reject=false;
|
||||||
switch(opcode) {
|
switch(opcode) {
|
||||||
|
|
||||||
case 'D':
|
case 'D':
|
||||||
@ -47,7 +47,8 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case '/': // New EXRAIL command
|
case '/': // New EXRAIL command
|
||||||
if (parseSlash(stream,paramCount,p)) opcode=0;
|
reject=!parseSlash(stream,paramCount,p);
|
||||||
|
opcode=0;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 'A': // <A address aspect>
|
case 'A': // <A address aspect>
|
||||||
@ -61,93 +62,53 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16
|
|||||||
case 'L':
|
case 'L':
|
||||||
// This entire code block is compiled out if LLC macros not used
|
// This entire code block is compiled out if LLC macros not used
|
||||||
if (!(compileFeatures & FEATURE_LCC)) return;
|
if (!(compileFeatures & FEATURE_LCC)) return;
|
||||||
static int lccProgCounter=0;
|
|
||||||
static int lccEventIndex=0;
|
|
||||||
|
|
||||||
if (paramCount==0) { //<L> LCC adapter introducing self
|
if (paramCount==0) { //<L> LCC adapter introducing self
|
||||||
LCCSerial=stream; // now we know where to send events we raise
|
LCCSerial=stream; // now we know where to send events we raise
|
||||||
opcode=0; // flag command as intercepted
|
|
||||||
|
|
||||||
// loop through all possible sent/waited events
|
// loop through all possible sent events
|
||||||
for (int progCounter=lccProgCounter;; SKIPOP) {
|
for (int progCounter=0;; SKIPOP) {
|
||||||
byte exrailOpcode=GET_OPCODE;
|
byte opcode=GET_OPCODE;
|
||||||
switch (exrailOpcode) {
|
if (opcode==OPCODE_ENDEXRAIL) break;
|
||||||
case OPCODE_ENDEXRAIL:
|
if (opcode==OPCODE_LCC) StringFormatter::send(stream,F("<LS x%h>\n"),getOperand(progCounter,0));
|
||||||
stream->print(F("<LR>\n")); // ready to roll
|
if (opcode==OPCODE_LCCX) { // long form LCC
|
||||||
lccProgCounter=0; // allow a second pass
|
StringFormatter::send(stream,F("<LS x%h%h%h%h>\n"),
|
||||||
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,1),
|
||||||
getOperand(progCounter,2),
|
getOperand(progCounter,2),
|
||||||
getOperand(progCounter,3),
|
getOperand(progCounter,3),
|
||||||
getOperand(progCounter,0)
|
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
|
// we stream the hex events we wish to listen to
|
||||||
// and at the same time build the event index looku.
|
// and at the same time build the event index looku.
|
||||||
|
|
||||||
case OPCODE_ONLCC:
|
|
||||||
|
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...
|
||||||
StringFormatter::send(stream,F("<LL %d x%h%h%h:%h>\n"),
|
StringFormatter::send(stream,F("<LL %d x%h%h%h:%h>\n"),
|
||||||
lccEventIndex,
|
eventIndex,
|
||||||
getOperand(progCounter,1),
|
getOperand(progCounter,1),
|
||||||
getOperand(progCounter,2),
|
getOperand(progCounter,2),
|
||||||
getOperand(progCounter,3),
|
getOperand(progCounter,3),
|
||||||
getOperand(progCounter,0)
|
getOperand(progCounter,0)
|
||||||
);
|
);
|
||||||
SKIPOP;SKIPOP;SKIPOP;SKIPOP;
|
eventIndex++;
|
||||||
// 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
|
if (paramCount==1) { // <L eventid> LCC event arrived from adapter
|
||||||
int16_t eventid=p[0];
|
int16_t eventid=p[0];
|
||||||
bool reject = eventid<0 || eventid>=countLCCLookup;
|
reject=eventid<0 || eventid>=countLCCLookup;
|
||||||
if (!reject) {
|
if (!reject) startNonRecursiveTask(F("LCC"),eventid,onLCCLookup[eventid]);
|
||||||
startNonRecursiveTask(F("LCC"),eventid,onLCCLookup[eventid]);
|
opcode=0;
|
||||||
opcode=0;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -221,20 +182,12 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) {
|
|||||||
StringFormatter::send(stream, F("<* EXRAIL STATUS"));
|
StringFormatter::send(stream, F("<* EXRAIL STATUS"));
|
||||||
RMFT2 * task=loopTask;
|
RMFT2 * task=loopTask;
|
||||||
while(task) {
|
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"),
|
StringFormatter::send(stream,F("\nID=%d,PC=%d,LOCO=%d%c,SPEED=%d%c"),
|
||||||
(int)(task->taskId),task->progCounter,task->loco,
|
(int)(task->taskId),task->progCounter,task->loco,
|
||||||
task->invert?'I':' ',
|
task->invert?'I':' ',
|
||||||
task->speedo,
|
task->speedo,
|
||||||
task->forward?'F':'R'
|
task->forward?'F':'R'
|
||||||
);
|
);
|
||||||
}
|
|
||||||
task=task->next;
|
task=task->next;
|
||||||
if (task==loopTask) break;
|
if (task==loopTask) break;
|
||||||
}
|
}
|
||||||
@ -252,13 +205,12 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) {
|
|||||||
// do the signals
|
// do the signals
|
||||||
// flags[n] represents the state of the nth signal in the table
|
// flags[n] represents the state of the nth signal in the table
|
||||||
for (int sigslot=0;;sigslot++) {
|
for (int sigslot=0;;sigslot++) {
|
||||||
int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8);
|
VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8);
|
||||||
if (sighandle==0) break; // end of signal list
|
if (sigid==0) break; // end of signal list
|
||||||
VPIN sigid = sighandle & SIGNAL_ID_MASK;
|
byte flag=flags[sigslot] & SIGNAL_MASK; // obtain signal flags for this id
|
||||||
byte flag=flags[sigslot] & SIGNAL_MASK; // obtain signal flags for this id
|
|
||||||
StringFormatter::send(stream,F("\n%S[%d]"),
|
StringFormatter::send(stream,F("\n%S[%d]"),
|
||||||
(flag == SIGNAL_RED)? F("RED") : (flag==SIGNAL_GREEN) ? F("GREEN") : F("AMBER"),
|
(flag == SIGNAL_RED)? F("RED") : (flag==SIGNAL_GREEN) ? F("GREEN") : F("AMBER"),
|
||||||
sigid);
|
sigid & SIGNAL_ID_MASK);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -75,7 +75,7 @@
|
|||||||
// Pass 1 Implements aliases
|
// Pass 1 Implements aliases
|
||||||
#include "EXRAIL2MacroReset.h"
|
#include "EXRAIL2MacroReset.h"
|
||||||
#undef ALIAS
|
#undef ALIAS
|
||||||
#define ALIAS(name,value...) const int name= #value[0] ? value+0: -__COUNTER__ ;
|
#define ALIAS(name,value...) const int name= 1##value##0 ==10 ? -__COUNTER__ : value##0/10;
|
||||||
#include "myAutomation.h"
|
#include "myAutomation.h"
|
||||||
|
|
||||||
// Pass 1d Detect sequence duplicates.
|
// Pass 1d Detect sequence duplicates.
|
||||||
@ -95,14 +95,14 @@ constexpr int16_t stuffSize=sizeof(compileTimeSequenceList)/sizeof(int16_t) - 1;
|
|||||||
|
|
||||||
|
|
||||||
// Compile time function to check for sequence nos.
|
// Compile time function to check for sequence nos.
|
||||||
constexpr bool hasseq(const int16_t value, const int16_t pos=0 ) {
|
constexpr bool hasseq(const int16_t value, const uint16_t pos=0 ) {
|
||||||
return pos>=stuffSize? false :
|
return pos>=stuffSize? false :
|
||||||
compileTimeSequenceList[pos]==value
|
compileTimeSequenceList[pos]==value
|
||||||
|| hasseq(value,pos+1);
|
|| hasseq(value,pos+1);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Compile time function to check for duplicate sequence nos.
|
// Compile time function to check for duplicate sequence nos.
|
||||||
constexpr bool hasdup(const int16_t value, const int16_t pos ) {
|
constexpr bool hasdup(const int16_t value, const uint16_t pos ) {
|
||||||
return pos>=stuffSize? false :
|
return pos>=stuffSize? false :
|
||||||
compileTimeSequenceList[pos]==value
|
compileTimeSequenceList[pos]==value
|
||||||
|| hasseq(value,pos+1)
|
|| hasseq(value,pos+1)
|
||||||
@ -118,8 +118,8 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU
|
|||||||
// This pass generates no runtime data or code
|
// This pass generates no runtime data or code
|
||||||
#include "EXRAIL2MacroReset.h"
|
#include "EXRAIL2MacroReset.h"
|
||||||
#undef ASPECT
|
#undef ASPECT
|
||||||
#define ASPECT(address,value) static_assert(address <=2044, "invalid Address"); \
|
#define ASPECT(address,value) static_assert((address & 0x7ff)== address, "invalid Address"); \
|
||||||
static_assert(address>=-3, "Invalid value");
|
static_assert((value & 0x1F)== value, "Invalid value");
|
||||||
#undef CALL
|
#undef CALL
|
||||||
#define CALL(id) static_assert(hasseq(id),"Sequence not found");
|
#define CALL(id) static_assert(hasseq(id),"Sequence not found");
|
||||||
#undef FOLLOW
|
#undef FOLLOW
|
||||||
@ -145,12 +145,6 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU
|
|||||||
|
|
||||||
#include "myAutomation.h"
|
#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
|
// Pass 1h Implements HAL macro by creating exrailHalSetup function
|
||||||
// Also allows creating EXTurntable object
|
// Also allows creating EXTurntable object
|
||||||
#include "EXRAIL2MacroReset.h"
|
#include "EXRAIL2MacroReset.h"
|
||||||
@ -189,14 +183,6 @@ bool exrailHalSetup() {
|
|||||||
#define LCCX(senderid,eventid) | FEATURE_LCC
|
#define LCCX(senderid,eventid) | FEATURE_LCC
|
||||||
#undef ONLCC
|
#undef ONLCC
|
||||||
#define ONLCC(senderid,eventid) | FEATURE_LCC
|
#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
|
#undef ROUTE_ACTIVE
|
||||||
#define ROUTE_ACTIVE(id) | FEATURE_ROUTESTATE
|
#define ROUTE_ACTIVE(id) | FEATURE_ROUTESTATE
|
||||||
#undef ROUTE_INACTIVE
|
#undef ROUTE_INACTIVE
|
||||||
@ -216,12 +202,6 @@ bool exrailHalSetup() {
|
|||||||
#define PICKUP_STASH(id) | FEATURE_STASH
|
#define PICKUP_STASH(id) | FEATURE_STASH
|
||||||
#undef STASH
|
#undef STASH
|
||||||
#define STASH(id) | FEATURE_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
|
const byte RMFT2::compileFeatures = 0
|
||||||
#include "myAutomation.h"
|
#include "myAutomation.h"
|
||||||
@ -273,9 +253,6 @@ const int StringMacroTracker1=__COUNTER__;
|
|||||||
#define PRINT(msg) THRUNGE(msg,thrunge_print)
|
#define PRINT(msg) THRUNGE(msg,thrunge_print)
|
||||||
#undef LCN
|
#undef LCN
|
||||||
#define LCN(msg) THRUNGE(msg,thrunge_lcn)
|
#define LCN(msg) THRUNGE(msg,thrunge_lcn)
|
||||||
#undef MESSAGE
|
|
||||||
#define MESSAGE(msg) THRUNGE(msg,thrunge_message)
|
|
||||||
|
|
||||||
#undef ROUTE_CAPTION
|
#undef ROUTE_CAPTION
|
||||||
#define ROUTE_CAPTION(id,caption) \
|
#define ROUTE_CAPTION(id,caption) \
|
||||||
case (__COUNTER__ - StringMacroTracker1) : {\
|
case (__COUNTER__ - StringMacroTracker1) : {\
|
||||||
@ -373,8 +350,6 @@ const FSH * RMFT2::getTurntableDescription(int16_t turntableId) {
|
|||||||
#define TT_ADDPOSITION(turntable_id,position,value,home,description...) T_DESC(turntable_id,position,description)
|
#define TT_ADDPOSITION(turntable_id,position,value,home,description...) T_DESC(turntable_id,position,description)
|
||||||
|
|
||||||
const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) {
|
const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) {
|
||||||
(void)turntableId;
|
|
||||||
(void)positionId;
|
|
||||||
#include "myAutomation.h"
|
#include "myAutomation.h"
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
@ -437,14 +412,10 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = {
|
|||||||
#include "myAutomation.h"
|
#include "myAutomation.h"
|
||||||
0,0,0,0 };
|
0,0,0,0 };
|
||||||
|
|
||||||
// Pass 9 ONLCC/ ONMERG counter and lookup array
|
// Pass 9 ONLCC counter and lookup array
|
||||||
#include "EXRAIL2MacroReset.h"
|
#include "EXRAIL2MacroReset.h"
|
||||||
#undef ONLCC
|
#undef ONLCC
|
||||||
#define ONLCC(sender,event) +1
|
#define ONLCC(sender,event) +1
|
||||||
#undef ONACON
|
|
||||||
#define ONACON(event) +1
|
|
||||||
#undef ONACOF
|
|
||||||
#define ONACOF(event) +1
|
|
||||||
|
|
||||||
const int RMFT2::countLCCLookup=0
|
const int RMFT2::countLCCLookup=0
|
||||||
#include "myAutomation.h"
|
#include "myAutomation.h"
|
||||||
@ -475,7 +446,6 @@ 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 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 AUTOMATION(id, description) OPCODE_AUTOMATION, V(id),
|
||||||
#define AUTOSTART OPCODE_AUTOSTART,0,0,
|
#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 BROADCAST(msg) PRINT(msg)
|
||||||
#define CALL(route) OPCODE_CALL,V(route),
|
#define CALL(route) OPCODE_CALL,V(route),
|
||||||
#define CLEAR_STASH(id) OPCODE_CLEAR_STASH,V(id),
|
#define CLEAR_STASH(id) OPCODE_CLEAR_STASH,V(id),
|
||||||
@ -509,7 +479,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
|
|||||||
#define FON(func) OPCODE_FON,V(func),
|
#define FON(func) OPCODE_FON,V(func),
|
||||||
#define FORGET OPCODE_FORGET,0,0,
|
#define FORGET OPCODE_FORGET,0,0,
|
||||||
#define FREE(blockid) OPCODE_FREE,V(blockid),
|
#define FREE(blockid) OPCODE_FREE,V(blockid),
|
||||||
#define FTOGGLE(func) OPCODE_FTOGGLE,V(func),
|
|
||||||
#define FWD(speed) OPCODE_FWD,V(speed),
|
#define FWD(speed) OPCODE_FWD,V(speed),
|
||||||
#define GREEN(signal_id) OPCODE_GREEN,V(signal_id),
|
#define GREEN(signal_id) OPCODE_GREEN,V(signal_id),
|
||||||
#define HAL(haltype,params...)
|
#define HAL(haltype,params...)
|
||||||
@ -541,16 +510,10 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
|
|||||||
OPCODE_PAD,V((((uint64_t)sender)>>32)&0xFFFF),\
|
OPCODE_PAD,V((((uint64_t)sender)>>32)&0xFFFF),\
|
||||||
OPCODE_PAD,V((((uint64_t)sender)>>16)&0xFFFF),\
|
OPCODE_PAD,V((((uint64_t)sender)>>16)&0xFFFF),\
|
||||||
OPCODE_PAD,V((((uint64_t)sender)>>0)&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 LCD(id,msg) PRINT(msg)
|
||||||
#define SCREEN(display,id,msg) PRINT(msg)
|
#define SCREEN(display,id,msg) PRINT(msg)
|
||||||
#define STEALTH(code...) PRINT(dummy)
|
#define STEALTH(code...) PRINT(dummy)
|
||||||
#define STEALTH_GLOBAL(code...)
|
|
||||||
#define LCN(msg) PRINT(msg)
|
#define LCN(msg) PRINT(msg)
|
||||||
#define MESSAGE(msg) PRINT(msg)
|
|
||||||
#define MOVETT(id,steps,activity) OPCODE_SERVO,V(id),OPCODE_PAD,V(steps),OPCODE_PAD,V(EXTurntable::activity),OPCODE_PAD,V(0),
|
#define MOVETT(id,steps,activity) OPCODE_SERVO,V(id),OPCODE_PAD,V(steps),OPCODE_PAD,V(EXTurntable::activity),OPCODE_PAD,V(0),
|
||||||
#define ONACTIVATE(addr,subaddr) OPCODE_ONACTIVATE,V(addr<<2|subaddr),
|
#define ONACTIVATE(addr,subaddr) OPCODE_ONACTIVATE,V(addr<<2|subaddr),
|
||||||
#define ONACTIVATEL(linear) OPCODE_ONACTIVATE,V(linear+3),
|
#define ONACTIVATEL(linear) OPCODE_ONACTIVATE,V(linear+3),
|
||||||
@ -573,8 +536,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
|
|||||||
#endif
|
#endif
|
||||||
#define ONTHROW(turnout_id) OPCODE_ONTHROW,V(turnout_id),
|
#define ONTHROW(turnout_id) OPCODE_ONTHROW,V(turnout_id),
|
||||||
#define ONCHANGE(sensor_id) OPCODE_ONCHANGE,V(sensor_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 PAUSE OPCODE_PAUSE,0,0,
|
||||||
#define PICKUP_STASH(id) OPCODE_PICKUP_STASH,V(id),
|
#define PICKUP_STASH(id) OPCODE_PICKUP_STASH,V(id),
|
||||||
#define PIN_TURNOUT(id,pin,description...) OPCODE_PINTURNOUT,V(id),OPCODE_PAD,V(pin),
|
#define PIN_TURNOUT(id,pin,description...) OPCODE_PINTURNOUT,V(id),OPCODE_PAD,V(pin),
|
||||||
@ -620,7 +581,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
|
|||||||
#define SET_TRACK(track,mode) OPCODE_SET_TRACK,V(TRACK_MODE_##mode <<8 | TRACK_NUMBER_##track),
|
#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 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 SETLOCO(loco) OPCODE_SETLOCO,V(loco),
|
||||||
#define SETFREQ(loco,freq) OPCODE_SETLOCO,V(loco), OPCODE_SETFREQ,V(freq),
|
|
||||||
#define SIGNAL(redpin,amberpin,greenpin)
|
#define SIGNAL(redpin,amberpin,greenpin)
|
||||||
#define SIGNALH(redpin,amberpin,greenpin)
|
#define SIGNALH(redpin,amberpin,greenpin)
|
||||||
#define SPEED(speed) OPCODE_SPEED,V(speed),
|
#define SPEED(speed) OPCODE_SPEED,V(speed),
|
||||||
@ -628,7 +588,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
|
|||||||
#define STASH(id) OPCODE_STASH,V(id),
|
#define STASH(id) OPCODE_STASH,V(id),
|
||||||
#define STOP OPCODE_SPEED,V(0),
|
#define STOP OPCODE_SPEED,V(0),
|
||||||
#define THROW(id) OPCODE_THROW,V(id),
|
#define THROW(id) OPCODE_THROW,V(id),
|
||||||
#define TOGGLE_TURNOUT(id) OPCODE_TOGGLE_TURNOUT,V(id),
|
|
||||||
#ifndef IO_NO_HAL
|
#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),
|
#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
|
#endif
|
||||||
@ -645,7 +604,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
|
|||||||
#endif
|
#endif
|
||||||
#define XFOFF(cab,func) OPCODE_XFOFF,V(cab),OPCODE_PAD,V(func),
|
#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 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
|
// Build RouteCode
|
||||||
const int StringMacroTracker2=__COUNTER__;
|
const int StringMacroTracker2=__COUNTER__;
|
||||||
|
104
EXRAILSensor.cpp
104
EXRAILSensor.cpp
@ -1,104 +0,0 @@
|
|||||||
/*
|
|
||||||
* © 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;
|
|
@ -1,50 +0,0 @@
|
|||||||
/*
|
|
||||||
* © 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-202406182019Z"
|
#define GITHUB_SHA "devel-202402171752Z"
|
||||||
|
@ -51,7 +51,6 @@ static void create(I2CAddress i2cAddress) {
|
|||||||
// Start by assuming we will find the clock
|
// Start by assuming we will find the clock
|
||||||
// Check if specified I2C address is responding (blocking operation)
|
// Check if specified I2C address is responding (blocking operation)
|
||||||
// Returns I2C_STATUS_OK (0) if OK, or error code.
|
// Returns I2C_STATUS_OK (0) if OK, or error code.
|
||||||
I2CManager.begin();
|
|
||||||
uint8_t _checkforclock = I2CManager.checkAddress(i2cAddress);
|
uint8_t _checkforclock = I2CManager.checkAddress(i2cAddress);
|
||||||
DIAG(F("Clock check result - %d"), _checkforclock);
|
DIAG(F("Clock check result - %d"), _checkforclock);
|
||||||
// XXXX change thistosave2 bytes
|
// XXXX change thistosave2 bytes
|
||||||
|
@ -83,7 +83,6 @@ void EXTurntable::_loop(unsigned long currentMicros) {
|
|||||||
// Read returns status as obtained in our loop.
|
// Read returns status as obtained in our loop.
|
||||||
// Return false if our status value is invalid.
|
// Return false if our status value is invalid.
|
||||||
int EXTurntable::_read(VPIN vpin) {
|
int EXTurntable::_read(VPIN vpin) {
|
||||||
(void)vpin; // surpress warning
|
|
||||||
if (_deviceState == DEVSTATE_FAILED) return 0;
|
if (_deviceState == DEVSTATE_FAILED) return 0;
|
||||||
if (_stepperStatus > 1) {
|
if (_stepperStatus > 1) {
|
||||||
return false;
|
return false;
|
||||||
@ -128,8 +127,6 @@ void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_
|
|||||||
vpin, value, activity, duration);
|
vpin, value, activity, duration);
|
||||||
DIAG(F("I2CManager write I2C Address:%d stepsMSB:%d stepsLSB:%d activity:%d"),
|
DIAG(F("I2CManager write I2C Address:%d stepsMSB:%d stepsLSB:%d activity:%d"),
|
||||||
_I2CAddress.toString(), stepsMSB, stepsLSB, activity);
|
_I2CAddress.toString(), stepsMSB, stepsLSB, activity);
|
||||||
#else
|
|
||||||
(void)duration;
|
|
||||||
#endif
|
#endif
|
||||||
if (activity < 4) _stepperStatus = 1; // Tell the device driver Turntable-EX is busy
|
if (activity < 4) _stepperStatus = 1; // Tell the device driver Turntable-EX is busy
|
||||||
_previousStatus = _stepperStatus;
|
_previousStatus = _stepperStatus;
|
||||||
|
@ -1,9 +1,7 @@
|
|||||||
/*
|
/*
|
||||||
* © 2024, Paul Antoine
|
* © 2023, Neil McKechnie. All rights reserved.
|
||||||
* © 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
|
* This is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
@ -114,14 +112,13 @@ protected:
|
|||||||
// Fill buffer with spaces
|
// Fill buffer with spaces
|
||||||
memset(_buffer, ' ', _numCols*_numRows);
|
memset(_buffer, ' ', _numCols*_numRows);
|
||||||
|
|
||||||
|
_displayDriver->clearNative();
|
||||||
|
|
||||||
// Add device to list of HAL devices (not necessary but allows
|
// Add device to list of HAL devices (not necessary but allows
|
||||||
// status to be displayed using <D HAL SHOW> and device to be
|
// status to be displayed using <D HAL SHOW> and device to be
|
||||||
// reinitialised using <D HAL RESET>).
|
// reinitialised using <D HAL RESET>).
|
||||||
IODevice::addDevice(this);
|
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
|
// Also add this display to list of display handlers
|
||||||
DisplayInterface::addDisplay(displayNo);
|
DisplayInterface::addDisplay(displayNo);
|
||||||
|
|
||||||
|
@ -42,9 +42,9 @@
|
|||||||
* Defining in myAutomation.h requires the device driver to be included in addition to the HAL() statement. Examples:
|
* Defining in myAutomation.h requires the device driver to be included in addition to the HAL() statement. Examples:
|
||||||
*
|
*
|
||||||
* #include "IO_RotaryEncoder.h"
|
* #include "IO_RotaryEncoder.h"
|
||||||
* HAL(RotaryEncoder, 700, 1, 0x67) // Define single Vpin, no feedback or position sent to rotary encoder software
|
* HAL(RotaryEncoder, 700, 1, 0x70) // Define single Vpin, no feedback or position sent to rotary encoder software
|
||||||
* HAL(RotaryEncoder, 700, 2, 0x67) // Define two Vpins, feedback only sent to rotary encoder software
|
* HAL(RotaryEncoder, 700, 2, 0x70) // Define two Vpins, feedback only sent to rotary encoder software
|
||||||
* HAL(RotaryEncoder, 700, 3, 0x67) // Define three Vpins, can send feedback and position update to rotary encoder software
|
* HAL(RotaryEncoder, 700, 3, 0x70) // Define three Vpins, can send feedback and position update to rotary encoder software
|
||||||
*
|
*
|
||||||
* Refer to the documentation for further information including the valid activities and examples.
|
* Refer to the documentation for further information including the valid activities and examples.
|
||||||
*/
|
*/
|
||||||
|
@ -26,7 +26,7 @@
|
|||||||
Thus "MAIN"_hk generates exactly the same run time vakue
|
Thus "MAIN"_hk generates exactly the same run time vakue
|
||||||
as const int16_t HASH_KEYWORD_MAIN=11339
|
as const int16_t HASH_KEYWORD_MAIN=11339
|
||||||
*/
|
*/
|
||||||
#ifndef KeywordHasher_h
|
#ifndef KeywordHAsher_h
|
||||||
#define KeywordHasher_h
|
#define KeywordHasher_h
|
||||||
|
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
|
158
MotorDriver.cpp
158
MotorDriver.cpp
@ -1,5 +1,5 @@
|
|||||||
/*
|
/*
|
||||||
* © 2022-2024 Paul M Antoine
|
* © 2022-2023 Paul M Antoine
|
||||||
* © 2021 Mike S
|
* © 2021 Mike S
|
||||||
* © 2021 Fred Decker
|
* © 2021 Fred Decker
|
||||||
* © 2020-2023 Harald Barth
|
* © 2020-2023 Harald Barth
|
||||||
@ -38,8 +38,6 @@ volatile portreg_t shadowPORTC;
|
|||||||
volatile portreg_t shadowPORTD;
|
volatile portreg_t shadowPORTD;
|
||||||
volatile portreg_t shadowPORTE;
|
volatile portreg_t shadowPORTE;
|
||||||
volatile portreg_t shadowPORTF;
|
volatile portreg_t shadowPORTF;
|
||||||
volatile portreg_t shadowPORTG;
|
|
||||||
volatile portreg_t shadowPORTH;
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin,
|
MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin,
|
||||||
@ -90,16 +88,6 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
|
|||||||
fastSignalPin.shadowinout = fastSignalPin.inout;
|
fastSignalPin.shadowinout = fastSignalPin.inout;
|
||||||
fastSignalPin.inout = &shadowPORTF;
|
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 = &shadowPORTF;
|
|
||||||
}
|
|
||||||
|
|
||||||
signalPin2=signal_pin2;
|
signalPin2=signal_pin2;
|
||||||
if (signalPin2!=UNUSED_PIN) {
|
if (signalPin2!=UNUSED_PIN) {
|
||||||
@ -138,16 +126,6 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
|
|||||||
fastSignalPin2.shadowinout = fastSignalPin2.inout;
|
fastSignalPin2.shadowinout = fastSignalPin2.inout;
|
||||||
fastSignalPin2.inout = &shadowPORTF;
|
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;
|
else dualSignal=false;
|
||||||
|
|
||||||
@ -347,21 +325,49 @@ uint16_t taurustones[28] = { 165, 175, 196, 220,
|
|||||||
220, 196, 175, 165 };
|
220, 196, 175, 165 };
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/) {
|
void MotorDriver::setDCSignal(byte speedcode) {
|
||||||
if (brakePin == UNUSED_PIN)
|
if (brakePin == UNUSED_PIN)
|
||||||
return;
|
return;
|
||||||
|
switch(brakePin) {
|
||||||
|
#if defined(ARDUINO_AVR_UNO)
|
||||||
|
// Not worth doin something here as:
|
||||||
|
// If we are on pin 9 or 10 we are on Timer1 and we can not touch Timer1 as that is our DCC source.
|
||||||
|
// If we are on pin 5 or 6 we are on Timer 0 ad we can not touch Timer0 as that is millis() etc.
|
||||||
|
// We are most likely not on pin 3 or 11 as no known motor shield has that as brake.
|
||||||
|
#endif
|
||||||
|
#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)
|
||||||
|
case 9:
|
||||||
|
case 10:
|
||||||
|
// Timer2 (is differnet)
|
||||||
|
TCCR2A = (TCCR2A & B11111100) | B00000001; // set WGM1=0 and WGM0=1 phase correct PWM
|
||||||
|
TCCR2B = (TCCR2B & B11110000) | B00000110; // set WGM2=0 ; set divisor on timer 2 to 1/256 for 122.55Hz
|
||||||
|
//DIAG(F("2 A=%x B=%x"), TCCR2A, TCCR2B);
|
||||||
|
break;
|
||||||
|
case 6:
|
||||||
|
case 7:
|
||||||
|
case 8:
|
||||||
|
// Timer4
|
||||||
|
TCCR4A = (TCCR4A & B11111100) | B00000001; // set WGM0=1 and WGM1=0 for normal PWM 8-bit
|
||||||
|
TCCR4B = (TCCR4B & B11100000) | B00000100; // set WGM2=0 and WGM3=0 for normal PWM 8 bit and div 1/256 for 122.55Hz
|
||||||
|
break;
|
||||||
|
case 46:
|
||||||
|
case 45:
|
||||||
|
case 44:
|
||||||
|
// Timer5
|
||||||
|
TCCR5A = (TCCR5A & B11111100) | B00000001; // set WGM0=1 and WGM1=0 for normal PWM 8-bit
|
||||||
|
TCCR5B = (TCCR5B & B11100000) | B00000100; // set WGM2=0 and WGM3=0 for normal PWM 8 bit and div 1/256 for 122.55Hz
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
// spedcoode is a dcc speed & direction
|
// spedcoode is a dcc speed & direction
|
||||||
byte tSpeed=speedcode & 0x7F; // DCC Speed with 0,1 stop and speed steps 2 to 127
|
byte tSpeed=speedcode & 0x7F; // DCC Speed with 0,1 stop and speed steps 2 to 127
|
||||||
byte tDir=speedcode & 0x80;
|
byte tDir=speedcode & 0x80;
|
||||||
byte brake;
|
byte brake;
|
||||||
|
|
||||||
if (tSpeed <= 1) brake = 255;
|
|
||||||
else if (tSpeed >= 127) brake = 0;
|
|
||||||
else brake = 2 * (128-tSpeed);
|
|
||||||
|
|
||||||
{ // new block because of variable f
|
|
||||||
#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32)
|
#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32)
|
||||||
int f = frequency;
|
{
|
||||||
|
int f = 131;
|
||||||
#ifdef VARIABLE_TONES
|
#ifdef VARIABLE_TONES
|
||||||
if (tSpeed > 2) {
|
if (tSpeed > 2) {
|
||||||
if (tSpeed <= 58) {
|
if (tSpeed <= 58) {
|
||||||
@ -369,15 +375,19 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
//DIAG(F("Brake pin %d value %d freqency %d"), brakePin, brake, f);
|
DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup
|
||||||
DCCTimer::DCCEXanalogWrite(brakePin, brake, invertBrake);
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency
|
|
||||||
#else // all AVR here
|
|
||||||
DCCTimer::DCCEXanalogWriteFrequency(brakePin, frequency); // frequency steps
|
|
||||||
analogWrite(brakePin, invertBrake ? 255-brake : brake);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
if (tSpeed <= 1) brake = 255;
|
||||||
|
else if (tSpeed >= 127) brake = 0;
|
||||||
|
else brake = 2 * (128-tSpeed);
|
||||||
|
if (invertBrake)
|
||||||
|
brake=255-brake;
|
||||||
|
#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32)
|
||||||
|
DCCTimer::DCCEXanalogWrite(brakePin,brake);
|
||||||
|
#else
|
||||||
|
analogWrite(brakePin,brake);
|
||||||
|
#endif
|
||||||
//DIAG(F("DCSignal %d"), speedcode);
|
//DIAG(F("DCSignal %d"), speedcode);
|
||||||
if (HAVE_PORTA(fastSignalPin.shadowinout == &PORTA)) {
|
if (HAVE_PORTA(fastSignalPin.shadowinout == &PORTA)) {
|
||||||
noInterrupts();
|
noInterrupts();
|
||||||
@ -415,18 +425,6 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/)
|
|||||||
setSignal(tDir);
|
setSignal(tDir);
|
||||||
HAVE_PORTF(PORTF=shadowPORTF);
|
HAVE_PORTF(PORTF=shadowPORTF);
|
||||||
interrupts();
|
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 {
|
} else {
|
||||||
noInterrupts();
|
noInterrupts();
|
||||||
setSignal(tDir);
|
setSignal(tDir);
|
||||||
@ -436,28 +434,60 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/)
|
|||||||
void MotorDriver::throttleInrush(bool on) {
|
void MotorDriver::throttleInrush(bool on) {
|
||||||
if (brakePin == UNUSED_PIN)
|
if (brakePin == UNUSED_PIN)
|
||||||
return;
|
return;
|
||||||
if ( !(trackMode & (TRACK_MODE_MAIN | TRACK_MODE_PROG | TRACK_MODE_EXT | TRACK_MODE_BOOST)))
|
if ( !(trackMode & (TRACK_MODE_MAIN | TRACK_MODE_PROG | TRACK_MODE_EXT)))
|
||||||
return;
|
return;
|
||||||
byte duty = on ? 207 : 0; // duty of 81% at 62500Hz this gives pauses of 3usec
|
byte duty = on ? 208 : 0;
|
||||||
|
if (invertBrake)
|
||||||
|
duty = 255-duty;
|
||||||
#if defined(ARDUINO_ARCH_ESP32)
|
#if defined(ARDUINO_ARCH_ESP32)
|
||||||
if(on) {
|
if(on) {
|
||||||
DCCTimer::DCCEXInrushControlOn(brakePin, duty, invertBrake);
|
DCCTimer::DCCEXanalogWrite(brakePin,duty);
|
||||||
|
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 62500);
|
||||||
} else {
|
} else {
|
||||||
ledcDetachPin(brakePin); // not DCCTimer::DCCEXledcDetachPin() as we have not
|
ledcDetachPin(brakePin);
|
||||||
// registered the pin in the pin to channel array
|
|
||||||
}
|
}
|
||||||
#elif defined(ARDUINO_ARCH_STM32)
|
#elif defined(ARDUINO_ARCH_STM32)
|
||||||
if(on) {
|
if(on) {
|
||||||
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max
|
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 62500);
|
||||||
DCCTimer::DCCEXanalogWrite(brakePin,duty,invertBrake);
|
DCCTimer::DCCEXanalogWrite(brakePin,duty);
|
||||||
} else {
|
} else {
|
||||||
pinMode(brakePin, OUTPUT);
|
pinMode(brakePin, OUTPUT);
|
||||||
}
|
}
|
||||||
#else // all AVR here
|
#else
|
||||||
if (invertBrake)
|
|
||||||
duty = 255-duty;
|
|
||||||
if(on){
|
if(on){
|
||||||
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max
|
switch(brakePin) {
|
||||||
|
#if defined(ARDUINO_AVR_UNO)
|
||||||
|
// Not worth doin something here as:
|
||||||
|
// If we are on pin 9 or 10 we are on Timer1 and we can not touch Timer1 as that is our DCC source.
|
||||||
|
// If we are on pin 5 or 6 we are on Timer 0 ad we can not touch Timer0 as that is millis() etc.
|
||||||
|
// We are most likely not on pin 3 or 11 as no known motor shield has that as brake.
|
||||||
|
#endif
|
||||||
|
#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)
|
||||||
|
case 9:
|
||||||
|
case 10:
|
||||||
|
// Timer2 (is different)
|
||||||
|
TCCR2A = (TCCR2A & B11111100) | B00000011; // set WGM0=1 and WGM1=1 for fast PWM
|
||||||
|
TCCR2B = (TCCR2B & B11110000) | B00000001; // set WGM2=0 and prescaler div=1 (max)
|
||||||
|
DIAG(F("2 A=%x B=%x"), TCCR2A, TCCR2B);
|
||||||
|
break;
|
||||||
|
case 6:
|
||||||
|
case 7:
|
||||||
|
case 8:
|
||||||
|
// Timer4
|
||||||
|
TCCR4A = (TCCR4A & B11111100) | B00000001; // set WGM0=1 and WGM1=0 for fast PWM 8-bit
|
||||||
|
TCCR4B = (TCCR4B & B11100000) | B00001001; // set WGM2=1 and WGM3=0 for fast PWM 8 bit and div=1 (max)
|
||||||
|
break;
|
||||||
|
case 46:
|
||||||
|
case 45:
|
||||||
|
case 44:
|
||||||
|
// Timer5
|
||||||
|
TCCR5A = (TCCR5A & B11111100) | B00000001; // set WGM0=1 and WGM1=0 for fast PWM 8-bit
|
||||||
|
TCCR5B = (TCCR5B & B11100000) | B00001001; // set WGM2=1 and WGM3=0 for fast PWM 8 bit and div=1 (max)
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
analogWrite(brakePin,duty);
|
analogWrite(brakePin,duty);
|
||||||
#endif
|
#endif
|
||||||
@ -638,10 +668,6 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) {
|
|||||||
}
|
}
|
||||||
throttleInrush(false);
|
throttleInrush(false);
|
||||||
setPower(POWERMODE::ON);
|
setPower(POWERMODE::ON);
|
||||||
break;
|
|
||||||
}
|
|
||||||
if (goodtime > POWER_SAMPLE_ALERT_GOOD/2) {
|
|
||||||
throttleInrush(false);
|
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -1,5 +1,5 @@
|
|||||||
/*
|
/*
|
||||||
* © 2022-2024 Paul M. Antoine
|
* © 2022-2023 Paul M. Antoine
|
||||||
* © 2021 Mike S
|
* © 2021 Mike S
|
||||||
* © 2021 Fred Decker
|
* © 2021 Fred Decker
|
||||||
* © 2020 Chris Harlow
|
* © 2020 Chris Harlow
|
||||||
@ -26,7 +26,6 @@
|
|||||||
#include "FSH.h"
|
#include "FSH.h"
|
||||||
#include "IODevice.h"
|
#include "IODevice.h"
|
||||||
#include "DCCTimer.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.
|
// 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)
|
// RACK_MODE_DCX is (TRACK_MODE_DC|TRACK_MODE_INV)
|
||||||
@ -35,15 +34,9 @@ template<class T> inline T operator| (T a, T b) { return (T)((int)a | (int)b); }
|
|||||||
template<class T> inline T operator& (T a, T b) { return (T)((int)a & (int)b); }
|
template<class T> inline T operator& (T a, T b) { return (T)((int)a & (int)b); }
|
||||||
template<class T> inline T operator^ (T a, T b) { return (T)((int)a ^ (int)b); }
|
template<class T> inline T operator^ (T a, T b) { return (T)((int)a ^ (int)b); }
|
||||||
enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PROG = 4,
|
enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PROG = 4,
|
||||||
TRACK_MODE_DC = 8, TRACK_MODE_EXT = 16,
|
TRACK_MODE_DC = 8, TRACK_MODE_EXT = 16, TRACK_MODE_BOOST = 32,
|
||||||
#ifdef ARDUINO_ARCH_ESP32
|
TRACK_MODE_ALL = 62, // only to operate all tracks
|
||||||
TRACK_MODE_BOOST = 32,
|
TRACK_MODE_INV = 64, TRACK_MODE_DCX = 72 /*DC + INV*/, TRACK_MODE_AUTOINV = 128};
|
||||||
#else
|
|
||||||
TRACK_MODE_BOOST = 0,
|
|
||||||
#endif
|
|
||||||
TRACK_MODE_ALL = TRACK_MODE_MAIN|TRACK_MODE_PROG|TRACK_MODE_DC|TRACK_MODE_EXT|TRACK_MODE_BOOST,
|
|
||||||
TRACK_MODE_INV = 64,
|
|
||||||
TRACK_MODE_DCX = TRACK_MODE_DC|TRACK_MODE_INV, TRACK_MODE_AUTOINV = 128};
|
|
||||||
|
|
||||||
#define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH
|
#define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH
|
||||||
#define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW
|
#define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW
|
||||||
@ -84,14 +77,6 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO
|
|||||||
#define PORTF GPIOF->ODR
|
#define PORTF GPIOF->ODR
|
||||||
#define HAVE_PORTF(X) X
|
#define HAVE_PORTF(X) X
|
||||||
#endif
|
#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
|
#endif
|
||||||
|
|
||||||
// if macros not defined as pass-through we define
|
// if macros not defined as pass-through we define
|
||||||
@ -115,12 +100,6 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO
|
|||||||
#ifndef HAVE_PORTF
|
#ifndef HAVE_PORTF
|
||||||
#define HAVE_PORTF(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
|
#define HAVE_PORTF(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
|
||||||
#endif
|
#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
|
// Virtualised Motor shield 1-track hardware Interface
|
||||||
|
|
||||||
@ -160,8 +139,6 @@ extern volatile portreg_t shadowPORTC;
|
|||||||
extern volatile portreg_t shadowPORTD;
|
extern volatile portreg_t shadowPORTD;
|
||||||
extern volatile portreg_t shadowPORTE;
|
extern volatile portreg_t shadowPORTE;
|
||||||
extern volatile portreg_t shadowPORTF;
|
extern volatile portreg_t shadowPORTF;
|
||||||
extern volatile portreg_t shadowPORTG;
|
|
||||||
extern volatile portreg_t shadowPORTH;
|
|
||||||
|
|
||||||
enum class POWERMODE : byte { OFF, ON, OVERLOAD, ALERT };
|
enum class POWERMODE : byte { OFF, ON, OVERLOAD, ALERT };
|
||||||
|
|
||||||
@ -210,14 +187,13 @@ class MotorDriver {
|
|||||||
}
|
}
|
||||||
};
|
};
|
||||||
inline pinpair getSignalPin() { return pinpair(signalPin,signalPin2); };
|
inline pinpair getSignalPin() { return pinpair(signalPin,signalPin2); };
|
||||||
inline int8_t getBrakePinSigned() { return invertBrake ? -brakePin : brakePin; };
|
void setDCSignal(byte speedByte);
|
||||||
void setDCSignal(byte speedByte, uint8_t frequency=0);
|
|
||||||
void throttleInrush(bool on);
|
void throttleInrush(bool on);
|
||||||
inline void detachDCSignal() {
|
inline void detachDCSignal() {
|
||||||
#if defined(__arm__)
|
#if defined(__arm__)
|
||||||
pinMode(brakePin, OUTPUT);
|
pinMode(brakePin, OUTPUT);
|
||||||
#elif defined(ARDUINO_ARCH_ESP32)
|
#elif defined(ARDUINO_ARCH_ESP32)
|
||||||
DCCTimer::DCCEXledcDetachPin(brakePin);
|
ledcDetachPin(brakePin);
|
||||||
#else
|
#else
|
||||||
setDCSignal(128);
|
setDCSignal(128);
|
||||||
#endif
|
#endif
|
||||||
|
@ -1,7 +1,7 @@
|
|||||||
/*
|
/*
|
||||||
* © 2022-2023 Paul M. Antoine
|
* © 2022-2023 Paul M. Antoine
|
||||||
* © 2021 Fred Decker
|
* © 2021 Fred Decker
|
||||||
* © 2020-2024 Harald Barth
|
* © 2020-2023 Harald Barth
|
||||||
* (c) 2020 Chris Harlow. All rights reserved.
|
* (c) 2020 Chris Harlow. All rights reserved.
|
||||||
* (c) 2021 Fred Decker. All rights reserved.
|
* (c) 2021 Fred Decker. All rights reserved.
|
||||||
* (c) 2020 Harald Barth. All rights reserved.
|
* (c) 2020 Harald Barth. All rights reserved.
|
||||||
@ -57,10 +57,6 @@
|
|||||||
// of the brake pin on the motor bridge is inverted
|
// of the brake pin on the motor bridge is inverted
|
||||||
// (HIGH == release brake)
|
// (HIGH == release brake)
|
||||||
|
|
||||||
// You can have a CS wihout any possibility to do any track signal.
|
|
||||||
// That's strange but possible.
|
|
||||||
#define NO_SHIELD F("No shield at all")
|
|
||||||
|
|
||||||
// Arduino STANDARD Motor Shield, used on different architectures:
|
// Arduino STANDARD Motor Shield, used on different architectures:
|
||||||
|
|
||||||
#if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32)
|
#if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32)
|
||||||
@ -97,18 +93,6 @@
|
|||||||
new MotorDriver(25/* 3*/, 19/*12*/, UNUSED_PIN, 13/*9*/, 35/*A2*/, 1.27, 5000, 36 /*A4*/), \
|
new MotorDriver(25/* 3*/, 19/*12*/, UNUSED_PIN, 13/*9*/, 35/*A2*/, 1.27, 5000, 36 /*A4*/), \
|
||||||
new MotorDriver(23/*11*/, 18/*13*/, UNUSED_PIN, 12/*8*/, 34/*A3*/, 1.27, 5000, 39 /*A5*/)
|
new MotorDriver(23/*11*/, 18/*13*/, UNUSED_PIN, 12/*8*/, 34/*A3*/, 1.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
|
#else
|
||||||
// STANDARD shield on any Arduino Uno or Mega compatible with the original specification.
|
// STANDARD shield on any Arduino Uno or Mega compatible with the original specification.
|
||||||
#define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"), \
|
#define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"), \
|
||||||
|
@ -1,119 +0,0 @@
|
|||||||
// 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
|
|
@ -1,6 +1,6 @@
|
|||||||
/*
|
/*
|
||||||
* © 2022 Chris Harlow
|
* © 2022 Chris Harlow
|
||||||
* © 2022-2024 Harald Barth
|
* © 2022,2023 Harald Barth
|
||||||
* © 2023 Colin Murdoch
|
* © 2023 Colin Murdoch
|
||||||
* All rights reserved.
|
* All rights reserved.
|
||||||
*
|
*
|
||||||
@ -19,7 +19,6 @@
|
|||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
|
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
#include "defines.h"
|
|
||||||
#include "TrackManager.h"
|
#include "TrackManager.h"
|
||||||
#include "FSH.h"
|
#include "FSH.h"
|
||||||
#include "DCCWaveform.h"
|
#include "DCCWaveform.h"
|
||||||
@ -35,13 +34,13 @@
|
|||||||
|
|
||||||
#define APPLY_BY_MODE(findmode,function) \
|
#define APPLY_BY_MODE(findmode,function) \
|
||||||
FOR_EACH_TRACK(t) \
|
FOR_EACH_TRACK(t) \
|
||||||
if (track[t]->getMode() & findmode) \
|
if (track[t]->getMode()==findmode) \
|
||||||
track[t]->function;
|
track[t]->function;
|
||||||
|
|
||||||
MotorDriver * TrackManager::track[MAX_TRACKS] = { NULL };
|
MotorDriver * TrackManager::track[MAX_TRACKS];
|
||||||
int16_t TrackManager::trackDCAddr[MAX_TRACKS] = { 0 };
|
int16_t TrackManager::trackDCAddr[MAX_TRACKS];
|
||||||
|
|
||||||
int8_t TrackManager::lastTrack=-1;
|
byte TrackManager::lastTrack=0;
|
||||||
bool TrackManager::progTrackSyncMain=false;
|
bool TrackManager::progTrackSyncMain=false;
|
||||||
bool TrackManager::progTrackBoosted=false;
|
bool TrackManager::progTrackBoosted=false;
|
||||||
int16_t TrackManager::joinRelay=UNUSED_PIN;
|
int16_t TrackManager::joinRelay=UNUSED_PIN;
|
||||||
@ -183,7 +182,7 @@ void TrackManager::setDCSignal(int16_t cab, byte speedbyte) {
|
|||||||
FOR_EACH_TRACK(t) {
|
FOR_EACH_TRACK(t) {
|
||||||
if (trackDCAddr[t]!=cab && cab != 0) continue;
|
if (trackDCAddr[t]!=cab && cab != 0) continue;
|
||||||
if (track[t]->getMode() & TRACK_MODE_DC)
|
if (track[t]->getMode() & TRACK_MODE_DC)
|
||||||
track[t]->setDCSignal(speedbyte, DCC::getThrottleFrequency(trackDCAddr[t]));
|
track[t]->setDCSignal(speedbyte);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -219,7 +218,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
|
|||||||
if (mode & TRACK_MODE_BOOST) {
|
if (mode & TRACK_MODE_BOOST) {
|
||||||
//DIAG(F("Track=%c mode boost pin %d"),trackToSet+'A', p.pin);
|
//DIAG(F("Track=%c mode boost pin %d"),trackToSet+'A', p.pin);
|
||||||
pinMode(BOOSTER_INPUT, INPUT);
|
pinMode(BOOSTER_INPUT, INPUT);
|
||||||
gpio_matrix_in(BOOSTER_INPUT, SIG_IN_FUNC228_IDX, false); //pads 224 to 228 available as loopback
|
gpio_matrix_in(26, SIG_IN_FUNC228_IDX, false); //pads 224 to 228 available as loopback
|
||||||
gpio_matrix_out(p.pin, SIG_IN_FUNC228_IDX, false, false);
|
gpio_matrix_out(p.pin, SIG_IN_FUNC228_IDX, false, false);
|
||||||
if (p.invpin != UNUSED_PIN) {
|
if (p.invpin != UNUSED_PIN) {
|
||||||
gpio_matrix_out(p.invpin, SIG_IN_FUNC228_IDX, true /*inverted*/, false);
|
gpio_matrix_out(p.invpin, SIG_IN_FUNC228_IDX, true /*inverted*/, false);
|
||||||
@ -251,47 +250,18 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
|
|||||||
} else {
|
} else {
|
||||||
track[trackToSet]->makeProgTrack(false); // only the prog track knows it's type
|
track[trackToSet]->makeProgTrack(false); // only the prog track knows it's type
|
||||||
}
|
}
|
||||||
|
track[trackToSet]->setMode(mode);
|
||||||
|
trackDCAddr[trackToSet]=dcAddr;
|
||||||
|
|
||||||
// When a track is switched, we must clear any side effects of its previous
|
// When a track is switched, we must clear any side effects of its previous
|
||||||
// state, otherwise trains run away or just dont move.
|
// state, otherwise trains run away or just dont move.
|
||||||
|
|
||||||
// This can be done BEFORE the PWM-Timer evaluation (methinks)
|
// This can be done BEFORE the PWM-Timer evaluation (methinks)
|
||||||
if (mode & TRACK_MODE_DC) {
|
if (!(mode & TRACK_MODE_DC)) {
|
||||||
if (trackDCAddr[trackToSet] != dcAddr) {
|
|
||||||
// new or changed DC Addr, run the new setup
|
|
||||||
if (trackDCAddr[trackToSet] != 0) {
|
|
||||||
// if we change dcAddr and not only
|
|
||||||
// change from another mode,
|
|
||||||
// first detach old DC signal
|
|
||||||
track[trackToSet]->detachDCSignal();
|
|
||||||
}
|
|
||||||
#ifdef ARDUINO_ARCH_ESP32
|
|
||||||
int trackfound = -1;
|
|
||||||
FOR_EACH_TRACK(t) {
|
|
||||||
//DIAG(F("Checking track %c mode %x dcAddr %d"), 'A'+t, track[t]->getMode(), trackDCAddr[t]);
|
|
||||||
if (t != trackToSet // not our track
|
|
||||||
&& (track[t]->getMode() & TRACK_MODE_DC) // right mode
|
|
||||||
&& trackDCAddr[t] == dcAddr) { // right addr
|
|
||||||
//DIAG(F("Found track %c"), 'A'+t);
|
|
||||||
trackfound = t;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if (trackfound > -1) {
|
|
||||||
DCCTimer::DCCEXanalogCopyChannel(track[trackfound]->getBrakePinSigned(),
|
|
||||||
track[trackToSet]->getBrakePinSigned());
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
// set future DC Addr;
|
|
||||||
trackDCAddr[trackToSet]=dcAddr;
|
|
||||||
} else {
|
|
||||||
// DCC tracks need to have set the PWM to zero or they will not work.
|
// DCC tracks need to have set the PWM to zero or they will not work.
|
||||||
track[trackToSet]->detachDCSignal();
|
track[trackToSet]->detachDCSignal();
|
||||||
track[trackToSet]->setBrake(false);
|
track[trackToSet]->setBrake(false);
|
||||||
trackDCAddr[trackToSet]=0; // clear that an addr is set for DC as this is not a DC track
|
|
||||||
}
|
}
|
||||||
track[trackToSet]->setMode(mode);
|
|
||||||
|
|
||||||
// BOOST:
|
// BOOST:
|
||||||
// Leave it as is
|
// Leave it as is
|
||||||
@ -358,8 +328,8 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
|
|||||||
}
|
}
|
||||||
|
|
||||||
void TrackManager::applyDCSpeed(byte t) {
|
void TrackManager::applyDCSpeed(byte t) {
|
||||||
track[t]->setDCSignal(DCC::getThrottleSpeedByte(trackDCAddr[t]),
|
uint8_t speedByte=DCC::getThrottleSpeedByte(trackDCAddr[t]);
|
||||||
DCC::getThrottleFrequency(trackDCAddr[t]));
|
track[t]->setDCSignal(speedByte);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[])
|
bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[])
|
||||||
@ -391,14 +361,13 @@ bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[])
|
|||||||
if (params==2 && p[1]=="EXT"_hk) // <= id EXT>
|
if (params==2 && p[1]=="EXT"_hk) // <= id EXT>
|
||||||
return setTrackMode(p[0],TRACK_MODE_EXT);
|
return setTrackMode(p[0],TRACK_MODE_EXT);
|
||||||
#ifdef BOOSTER_INPUT
|
#ifdef BOOSTER_INPUT
|
||||||
if (TRACK_MODE_BOOST != 0 && // compile time optimization
|
if (params==2 && p[1]=="BOOST"_hk) // <= id BOOST>
|
||||||
params==2 && p[1]=="BOOST"_hk) // <= id BOOST>
|
|
||||||
return setTrackMode(p[0],TRACK_MODE_BOOST);
|
return setTrackMode(p[0],TRACK_MODE_BOOST);
|
||||||
#endif
|
#endif
|
||||||
if (params==2 && p[1]=="AUTO"_hk) // <= id AUTO>
|
if (params==2 && p[1]=="AUTO"_hk) // <= id AUTO>
|
||||||
return setTrackMode(p[0], track[p[0]]->getMode() | TRACK_MODE_AUTOINV);
|
return setTrackMode(p[0], track[p[0]]->getMode() | TRACK_MODE_AUTOINV);
|
||||||
|
|
||||||
if (params==2 && p[1]=="INV"_hk) // <= id INV>
|
if (params==2 && p[1]=="INV"_hk) // <= id AUTO>
|
||||||
return setTrackMode(p[0], track[p[0]]->getMode() | TRACK_MODE_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>
|
if (params==3 && p[1]=="DC"_hk && p[2]>0) // <= id DC cab>
|
||||||
@ -431,11 +400,11 @@ const FSH* TrackManager::getModeName(TRACK_MODE tm) {
|
|||||||
modename=F("EXT");
|
modename=F("EXT");
|
||||||
else if(tm & TRACK_MODE_BOOST) {
|
else if(tm & TRACK_MODE_BOOST) {
|
||||||
if(tm & TRACK_MODE_AUTOINV)
|
if(tm & TRACK_MODE_AUTOINV)
|
||||||
modename=F("BOOST A");
|
modename=F("B A");
|
||||||
else if (tm & TRACK_MODE_INV)
|
else if (tm & TRACK_MODE_INV)
|
||||||
modename=F("BOOST I");
|
modename=F("B I");
|
||||||
else
|
else
|
||||||
modename=F("BOOST");
|
modename=F("B");
|
||||||
}
|
}
|
||||||
else if (tm & TRACK_MODE_DC) {
|
else if (tm & TRACK_MODE_DC) {
|
||||||
if (tm & TRACK_MODE_INV)
|
if (tm & TRACK_MODE_INV)
|
||||||
@ -528,10 +497,6 @@ void TrackManager::setTrackPower(TRACK_MODE trackmodeToMatch, POWERMODE powermod
|
|||||||
// Set track power for this track, inependent of mode
|
// Set track power for this track, inependent of mode
|
||||||
void TrackManager::setTrackPower(POWERMODE powermode, byte t) {
|
void TrackManager::setTrackPower(POWERMODE powermode, byte t) {
|
||||||
MotorDriver *driver=track[t];
|
MotorDriver *driver=track[t];
|
||||||
if (driver == NULL) { // track is not defined at all
|
|
||||||
DIAG(F("Error: Track %c does not exist"), t+'A');
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
TRACK_MODE trackmode = driver->getMode();
|
TRACK_MODE trackmode = driver->getMode();
|
||||||
POWERMODE oldpower = driver->getPower();
|
POWERMODE oldpower = driver->getPower();
|
||||||
if (trackmode & TRACK_MODE_NONE) {
|
if (trackmode & TRACK_MODE_NONE) {
|
||||||
@ -589,17 +554,14 @@ bool TrackManager::getPower(byte t, char s[]) {
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void TrackManager::reportObsoleteCurrent(Print* stream) {
|
void TrackManager::reportObsoleteCurrent(Print* stream) {
|
||||||
// This function is for backward JMRI compatibility only
|
// This function is for backward JMRI compatibility only
|
||||||
// It reports the first track only, as main, regardless of track settings.
|
// It reports the first track only, as main, regardless of track settings.
|
||||||
// <c MeterName value C/V unit min max res warn>
|
// <c MeterName value C/V unit min max res warn>
|
||||||
#ifdef HAS_ENOUGH_MEMORY
|
|
||||||
int maxCurrent=track[0]->raw2mA(track[0]->getRawCurrentTripValue());
|
int maxCurrent=track[0]->raw2mA(track[0]->getRawCurrentTripValue());
|
||||||
StringFormatter::send(stream, F("<c CurrentMAIN %d C Milli 0 %d 1 %d>\n"),
|
StringFormatter::send(stream, F("<c CurrentMAIN %d C Milli 0 %d 1 %d>\n"),
|
||||||
track[0]->raw2mA(track[0]->getCurrentRaw(false)), maxCurrent, maxCurrent);
|
track[0]->raw2mA(track[0]->getCurrentRaw(false)), maxCurrent, maxCurrent);
|
||||||
#else
|
|
||||||
(void)stream;
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void TrackManager::reportCurrent(Print* stream) {
|
void TrackManager::reportCurrent(Print* stream) {
|
||||||
|
@ -1,6 +1,6 @@
|
|||||||
/*
|
/*
|
||||||
* © 2022 Chris Harlow
|
* © 2022 Chris Harlow
|
||||||
* © 2022-2024 Harald Barth
|
* © 2022 Harald Barth
|
||||||
* © 2023 Colin Murdoch
|
* © 2023 Colin Murdoch
|
||||||
*
|
*
|
||||||
* All rights reserved.
|
* All rights reserved.
|
||||||
@ -46,7 +46,7 @@ const byte TRACK_POWER_1=1, TRACK_POWER_ON=1;
|
|||||||
class TrackManager {
|
class TrackManager {
|
||||||
public:
|
public:
|
||||||
static void Setup(const FSH * shieldName,
|
static void Setup(const FSH * shieldName,
|
||||||
MotorDriver * track0=NULL,
|
MotorDriver * track0,
|
||||||
MotorDriver * track1=NULL,
|
MotorDriver * track1=NULL,
|
||||||
MotorDriver * track2=NULL,
|
MotorDriver * track2=NULL,
|
||||||
MotorDriver * track3=NULL,
|
MotorDriver * track3=NULL,
|
||||||
@ -108,7 +108,7 @@ class TrackManager {
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
static void addTrack(byte t, MotorDriver* driver);
|
static void addTrack(byte t, MotorDriver* driver);
|
||||||
static int8_t lastTrack;
|
static byte lastTrack;
|
||||||
static byte nextCycleTrack;
|
static byte nextCycleTrack;
|
||||||
static void applyDCSpeed(byte t);
|
static void applyDCSpeed(byte t);
|
||||||
|
|
||||||
|
@ -123,6 +123,7 @@
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#define DIAG_IO
|
||||||
// Static setClosed function is invoked from close(), throw() etc. to perform the
|
// 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
|
// 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
|
// type should be placed in the virtual function setClosedInternal(bool) which is
|
||||||
|
@ -247,23 +247,22 @@ DCCTurntable::DCCTurntable(uint16_t id) : Turntable(id, TURNTABLE_DCC) {}
|
|||||||
StringFormatter::send(stream, F("<i %d DCCTURNTABLE>\n"), _turntableData.id);
|
StringFormatter::send(stream, F("<i %d DCCTURNTABLE>\n"), _turntableData.id);
|
||||||
}
|
}
|
||||||
|
|
||||||
// EX-Turntable specific code for moving to the specified position
|
// EX-Turntable specific code for moving to the specified position
|
||||||
bool DCCTurntable::setPositionInternal(uint8_t position, uint8_t activity) {
|
bool DCCTurntable::setPositionInternal(uint8_t position, uint8_t activity) {
|
||||||
(void) activity;
|
|
||||||
#ifndef IO_NO_HAL
|
#ifndef IO_NO_HAL
|
||||||
int16_t value = getPositionValue(position);
|
int16_t value = getPositionValue(position);
|
||||||
if (position == 0 || !value) return false; // Return false if it's not a valid position
|
if (position == 0 || !value) return false; // Return false if it's not a valid position
|
||||||
// Set position via device driver
|
// Set position via device driver
|
||||||
int16_t addr=value>>3;
|
int16_t addr=value>>3;
|
||||||
int16_t subaddr=(value>>1) & 0x03;
|
int16_t subaddr=(value>>1) & 0x03;
|
||||||
bool active=value & 0x01;
|
bool active=value & 0x01;
|
||||||
_previousPosition = _turntableData.position;
|
_previousPosition = _turntableData.position;
|
||||||
_turntableData.position = position;
|
_turntableData.position = position;
|
||||||
DCC::setAccessory(addr, subaddr, active);
|
DCC::setAccessory(addr, subaddr, active);
|
||||||
#else
|
#else
|
||||||
(void)position;
|
(void)position;
|
||||||
#endif
|
#endif
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -571,7 +571,7 @@ void WiThrottle::sendRoutes(Print* stream) {
|
|||||||
|
|
||||||
void WiThrottle::sendFunctions(Print* stream, byte loco) {
|
void WiThrottle::sendFunctions(Print* stream, byte loco) {
|
||||||
int16_t locoid=myLocos[loco].cab;
|
int16_t locoid=myLocos[loco].cab;
|
||||||
int fkeys=32; // upper limit (send functions 0 to 31)
|
int fkeys=29;
|
||||||
myLocos[loco].functionToggles=1<<2; // F2 (HORN) is a non-toggle
|
myLocos[loco].functionToggles=1<<2; // F2 (HORN) is a non-toggle
|
||||||
|
|
||||||
#ifdef EXRAIL_ACTIVE
|
#ifdef EXRAIL_ACTIVE
|
||||||
@ -621,7 +621,7 @@ void WiThrottle::sendFunctions(Print* stream, byte loco) {
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
for(int fKey=0; fKey<fkeys; fKey++) {
|
for(int fKey=0; fKey<fkeys; fKey++) {
|
||||||
int8_t fstate=DCC::getFn(locoid,fKey);
|
int fstate=DCC::getFn(locoid,fKey);
|
||||||
if (fstate>=0) StringFormatter::send(stream,F("M%cA%c%d<;>F%d%d\n"),myLocos[loco].throttle,LorS(locoid),locoid,fstate,fKey);
|
if (fstate>=0) StringFormatter::send(stream,F("M%cA%c%d<;>F%d%d\n"),myLocos[loco].throttle,LorS(locoid),locoid,fstate,fKey);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -147,12 +147,6 @@ bool WifiESP::setup(const char *SSid,
|
|||||||
// enableCoreWDT(1);
|
// enableCoreWDT(1);
|
||||||
// disableCoreWDT(0);
|
// disableCoreWDT(0);
|
||||||
|
|
||||||
#ifdef WIFI_LED
|
|
||||||
// Turn off Wifi LED
|
|
||||||
pinMode(WIFI_LED, OUTPUT);
|
|
||||||
digitalWrite(WIFI_LED, 0);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// clean start
|
// clean start
|
||||||
WiFi.mode(WIFI_STA);
|
WiFi.mode(WIFI_STA);
|
||||||
WiFi.disconnect(true);
|
WiFi.disconnect(true);
|
||||||
@ -253,13 +247,6 @@ bool WifiESP::setup(const char *SSid,
|
|||||||
// no idea to go on
|
// no idea to go on
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#ifdef WIFI_LED
|
|
||||||
else{
|
|
||||||
// Turn on Wifi connected LED
|
|
||||||
digitalWrite(WIFI_LED, 1);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
// Now Wifi is up, register the mDNS service
|
// Now Wifi is up, register the mDNS service
|
||||||
if(!MDNS.begin(hostname)) {
|
if(!MDNS.begin(hostname)) {
|
||||||
|
@ -1,5 +1,4 @@
|
|||||||
/*
|
/*
|
||||||
* © 2022-2024 Paul M. Antoine
|
|
||||||
* © 2021 Fred Decker
|
* © 2021 Fred Decker
|
||||||
* © 2020-2022 Harald Barth
|
* © 2020-2022 Harald Barth
|
||||||
* © 2020-2022 Chris Harlow
|
* © 2020-2022 Chris Harlow
|
||||||
@ -71,7 +70,7 @@ Stream * WifiInterface::wifiStream;
|
|||||||
#define SERIAL3 Serial5
|
#define SERIAL3 Serial5
|
||||||
#elif defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) \
|
#elif defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) \
|
||||||
|| defined(ARDUINO_NUCLEO_F446ZE) || defined(ARDUINO_NUCLEO_F412ZG) \
|
|| defined(ARDUINO_NUCLEO_F446ZE) || defined(ARDUINO_NUCLEO_F412ZG) \
|
||||||
|| defined(ARDUINO_NUCLEO_F439ZI) || defined(ARDUINO_NUCLEO_F4X9ZI)
|
|| defined(ARDUINO_NUCLEO_F439ZI)
|
||||||
#define NUM_SERIAL 2
|
#define NUM_SERIAL 2
|
||||||
#define SERIAL1 Serial6
|
#define SERIAL1 Serial6
|
||||||
#else
|
#else
|
||||||
|
@ -211,19 +211,6 @@ The configuration file for DCC-EX Command Station
|
|||||||
// #define DISABLE_VDPY
|
// #define DISABLE_VDPY
|
||||||
// #define ENABLE_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
|
// REDEFINE WHERE SHORT/LONG ADDR break is. According to NMRA the last short address
|
||||||
// is 127 and the first long address is 128. There are manufacturers which have
|
// is 127 and the first long address is 128. There are manufacturers which have
|
||||||
@ -307,21 +294,11 @@ The configuration file for DCC-EX Command Station
|
|||||||
//
|
//
|
||||||
//#define SERIAL_BT_COMMANDS
|
//#define SERIAL_BT_COMMANDS
|
||||||
|
|
||||||
// BOOSTER PIN INPUT ON ESP32 CS
|
// BOOSTER PIN INPUT ON ESP32
|
||||||
// On ESP32 you have the possibility to define a pin as booster input
|
// 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
|
//#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
|
// SABERTOOTH
|
||||||
//
|
//
|
||||||
|
@ -220,15 +220,9 @@
|
|||||||
//
|
//
|
||||||
#if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO)
|
#if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO)
|
||||||
#define IO_NO_HAL // HAL too big whatever you disable otherwise
|
#define IO_NO_HAL // HAL too big whatever you disable otherwise
|
||||||
|
|
||||||
#ifndef ENABLE_VDPY
|
#ifndef ENABLE_VDPY
|
||||||
#define DISABLE_VDPY
|
#define DISABLE_VDPY
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef ENABLE_DIAG
|
|
||||||
#define DISABLE_DIAG
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if __has_include ( "myAutomation.h")
|
#if __has_include ( "myAutomation.h")
|
||||||
|
@ -311,13 +311,12 @@ void halSetup() {
|
|||||||
//=======================================================================
|
//=======================================================================
|
||||||
// The parameters are:
|
// The parameters are:
|
||||||
// firstVpin = First available Vpin to allocate
|
// firstVpin = First available Vpin to allocate
|
||||||
// numPins= Number of Vpins to allocate, can be either 1 to 3
|
// numPins= Number of Vpins to allocate, can be either 1 or 2
|
||||||
// i2cAddress = Available I2C address (default 0x67)
|
// i2cAddress = Available I2C address (default 0x70)
|
||||||
|
|
||||||
//RotaryEncoder::create(firstVpin, numPins, i2cAddress);
|
//RotaryEncoder::create(firstVpin, numPins, i2cAddress);
|
||||||
//RotaryEncoder::create(700, 1, 0x67);
|
//RotaryEncoder::create(700, 1, 0x70);
|
||||||
//RotaryEncoder::create(700, 2, 0x67);
|
//RotaryEncoder::create(701, 2, 0x71);
|
||||||
//RotaryEncoder::create(700, 3, 0x67);
|
|
||||||
|
|
||||||
//=======================================================================
|
//=======================================================================
|
||||||
// The following directive defines an EX-FastClock instance.
|
// The following directive defines an EX-FastClock instance.
|
||||||
|
@ -164,11 +164,7 @@ monitor_echo = yes
|
|||||||
build_flags = -mcall-prologues
|
build_flags = -mcall-prologues
|
||||||
|
|
||||||
[env:ESP32]
|
[env:ESP32]
|
||||||
; Lock version to 6.7.0 as that is
|
platform = espressif32
|
||||||
; 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
|
board = esp32dev
|
||||||
framework = arduino
|
framework = arduino
|
||||||
lib_deps = ${env.lib_deps}
|
lib_deps = ${env.lib_deps}
|
||||||
|
45
version.h
45
version.h
@ -3,50 +3,7 @@
|
|||||||
|
|
||||||
#include "StringFormatter.h"
|
#include "StringFormatter.h"
|
||||||
|
|
||||||
#define VERSION "5.2.63"
|
#define VERSION "5.2.35"
|
||||||
// 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 woith Adapter base code)
|
|
||||||
// 5.2.60 - Bugfix: Opcode AFTEROVERLOAD does not have an argument that is a pin and needs to be initialized
|
|
||||||
// - Remove inrush throttle after half good time so that we go to mode overload if problem persists
|
|
||||||
// 5.2.59 - STM32 bugfix correct Serial1 definition for Nucleo-F401RE
|
|
||||||
// - STM32 add support for ARDUINO_NUCLEO_F4X9ZI type to span F429/F439 in upcoming STM32duino release v2.8 as a result of our PR
|
|
||||||
// 5.2.58 - EXRAIL ALIAS allows named pins
|
|
||||||
// 5.2.57 - Bugfix autoreverse: Apply mode by binart bit match and not by equality
|
|
||||||
// 5.2.56 - Bugfix and refactor for EXRAIL getSignalSlot
|
|
||||||
// 5.2.55 - Move EXRAIL isSignal() to public to allow use in STEALTH call
|
|
||||||
// 5.2.54 - Bugfix for EXRAIL signal handling for active high
|
|
||||||
// 5.2.53 - Bugfix for EX-Fastclock, call I2CManager.begin() before checking I2C address
|
|
||||||
// 5.2.52 - Bugfix for ADCee() to handle ADC2 and ADC3 channel inputs on F446ZE and others
|
|
||||||
// - Add support for ports G and H on STM32 for ADCee() and MotorDriver pins/shadow regs
|
|
||||||
// 5.2.51 - Bugfix for SIGNAL: Distinguish between sighandle and sigid
|
|
||||||
// 5.2.50 - EXRAIL ONBUTTON/ONSENSOR observe LATCH
|
|
||||||
// 5.2.49 - EXRAIL additions:
|
|
||||||
// ONBUTTON, ONSENSOR
|
|
||||||
// 5.2.48 - Bugfix: HALDisplay was generating I2C traffic prior to I2C being initialised
|
|
||||||
// 5.2.47 - EXRAIL additions:
|
|
||||||
// STEALTH_GLOBAL
|
|
||||||
// BLINK
|
|
||||||
// TOGGLE_TURNOUT
|
|
||||||
// FTOGGLE, XFTOGGLE
|
|
||||||
// Reduced code-developmenmt DIAG noise
|
|
||||||
// 5.2.46 - Support for extended consist CV20 in <R> and <W id>
|
|
||||||
// - New cmd <W CONSIST id [REVERSE]> to handle long/short consist ids
|
|
||||||
// 5.2.45 - ESP32 Trackmanager reset cab number to 0 when track is not DC
|
|
||||||
// ESP32 fix PWM LEDC inverted pin mode
|
|
||||||
// ESP32 rewrite PWM LEDC to use pin mux
|
|
||||||
// 5.2.42 - ESP32 Bugfix: Uninitialized stack variable
|
|
||||||
// 5.2.41 - Update rotary encoder default address to 0x67
|
|
||||||
// 5.2.40 - Allow no shield
|
|
||||||
// 5.2.39 - Functions for DC frequency: Use func up to F31
|
|
||||||
// 5.2.38 - Exrail MESSAGE("text") to send a user message to all
|
|
||||||
// connected throttles (uses <m "text"> and withrottle Hmtext.
|
|
||||||
// 5.2.37 - Bugfix ESP32: Use BOOSTER_INPUT define
|
|
||||||
// 5.2.36 - Variable frequency for DC mode
|
|
||||||
// 5.2.35 - Bugfix: Make DCC Extended Accessories follow RCN-213
|
// 5.2.35 - Bugfix: Make DCC Extended Accessories follow RCN-213
|
||||||
// 5.2.34 - <A address aspect> Command fopr DCC Extended Accessories
|
// 5.2.34 - <A address aspect> Command fopr DCC Extended Accessories
|
||||||
// - Exrail ASPECT(address,aspect) for above.
|
// - Exrail ASPECT(address,aspect) for above.
|
||||||
|
Loading…
Reference in New Issue
Block a user