mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-11-23 16:16:13 +01:00
Compare commits
34 Commits
8f0a5c1ec0
...
3fc90c916c
Author | SHA1 | Date | |
---|---|---|---|
|
3fc90c916c | ||
|
132e2d0de2 | ||
|
23845f2df2 | ||
|
76755993f1 | ||
|
91e60b3716 | ||
|
8a5a832b1d | ||
|
5ea6feb11a | ||
|
8987d622e6 | ||
|
263c3d01e3 | ||
|
182479c07b | ||
|
3317b4666e | ||
|
f41f61dd5f | ||
|
6b713bf57c | ||
|
38a9585a41 | ||
|
1a307eea3d | ||
|
e4a3aa9f1e | ||
|
f581d56bdc | ||
|
7b77d4ce1e | ||
|
d367f5dc81 | ||
|
dc5f5e05b9 | ||
|
cff4075937 | ||
|
84b90ae757 | ||
|
6d7d2325da | ||
|
fdc956576b | ||
|
28d60d4984 | ||
|
3b162996ad | ||
|
fb414a7a50 | ||
|
818e05b425 | ||
|
c5168f030f | ||
|
387ea019bd | ||
|
a981f83bb9 | ||
|
749a859db5 | ||
|
659c58b307 | ||
|
0b9ec7460b |
76
DCC.cpp
76
DCC.cpp
|
@ -325,8 +325,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ür den ersten erweiterten Zubehördecoder ist wie bei den einfachen
|
Die Adresse f<EFBFBD>r den ersten erweiterten Zubeh<EFBFBD>rdecoder ist wie bei den einfachen
|
||||||
Zubehördecodern die Adresse 4 = 1000-0001 0111-0001 . Diese Adresse wird in
|
Zubeh<EFBFBD>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,6 +500,36 @@ 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)
|
||||||
|
@ -566,6 +596,10 @@ 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
|
||||||
|
@ -581,9 +615,25 @@ 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
|
// 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 decoder without cv19 support
|
WB,WACK, // ignore decoder without cv19 support
|
||||||
|
@ -652,6 +702,26 @@ 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);
|
||||||
|
|
2
DCC.h
2
DCC.h
|
@ -85,7 +85,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
|
||||||
|
|
17
DCCACK.cpp
17
DCCACK.cpp
|
@ -314,6 +314,14 @@ 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
|
||||||
|
@ -322,6 +330,15 @@ 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:
|
||||||
|
|
2
DCCACK.h
2
DCCACK.h
|
@ -56,6 +56,8 @@ 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
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -458,6 +458,9 @@ 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
|
||||||
|
@ -1348,3 +1351,11 @@ 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,6 +71,7 @@ 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;
|
||||||
|
|
|
@ -65,7 +65,11 @@ 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);
|
static void DCCEXanalogWrite(uint8_t pin, int value, bool invert);
|
||||||
|
static void DCCEXledcDetachPin(uint8_t pin);
|
||||||
|
static void DCCEXanalogCopyChannel(int8_t frompin, int8_t topin);
|
||||||
|
static void DCCEXInrushControlOn(uint8_t pin, int duty, bool invert);
|
||||||
|
static void DCCEXledcAttachPin(uint8_t pin, int8_t channel, bool inverted);
|
||||||
|
|
||||||
// Update low ram level. Allow for extra bytes to be specified
|
// 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
|
||||||
|
|
|
@ -78,6 +78,7 @@ int DCCTimer::freeMemory() {
|
||||||
////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
#ifdef ARDUINO_ARCH_ESP32
|
#ifdef ARDUINO_ARCH_ESP32
|
||||||
|
#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>
|
||||||
|
@ -154,8 +155,10 @@ void DCCTimer::reset() {
|
||||||
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
|
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
|
||||||
if (f >= 16)
|
if (f >= 16)
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f);
|
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f);
|
||||||
else if (f == 7)
|
/*
|
||||||
|
else if (f == 7) // not used on ESP32
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 62500);
|
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 62500);
|
||||||
|
*/
|
||||||
else if (f >= 4)
|
else if (f >= 4)
|
||||||
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 32000);
|
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 32000);
|
||||||
else if (f >= 3)
|
else if (f >= 3)
|
||||||
|
@ -188,23 +191,104 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
|
void DCCTimer::DCCEXledcDetachPin(uint8_t pin) {
|
||||||
|
DIAG(F("Clear pin %d channel"), pin);
|
||||||
|
pin_to_channel[pin] = 0;
|
||||||
|
pinMatrixOutDetach(pin, false, false);
|
||||||
|
}
|
||||||
|
|
||||||
|
static byte LEDCToMux[] = {
|
||||||
|
LEDC_HS_SIG_OUT0_IDX,
|
||||||
|
LEDC_HS_SIG_OUT1_IDX,
|
||||||
|
LEDC_HS_SIG_OUT2_IDX,
|
||||||
|
LEDC_HS_SIG_OUT3_IDX,
|
||||||
|
LEDC_HS_SIG_OUT4_IDX,
|
||||||
|
LEDC_HS_SIG_OUT5_IDX,
|
||||||
|
LEDC_HS_SIG_OUT6_IDX,
|
||||||
|
LEDC_HS_SIG_OUT7_IDX,
|
||||||
|
LEDC_LS_SIG_OUT0_IDX,
|
||||||
|
LEDC_LS_SIG_OUT1_IDX,
|
||||||
|
LEDC_LS_SIG_OUT2_IDX,
|
||||||
|
LEDC_LS_SIG_OUT3_IDX,
|
||||||
|
LEDC_LS_SIG_OUT4_IDX,
|
||||||
|
LEDC_LS_SIG_OUT5_IDX,
|
||||||
|
LEDC_LS_SIG_OUT6_IDX,
|
||||||
|
LEDC_LS_SIG_OUT7_IDX,
|
||||||
|
};
|
||||||
|
|
||||||
|
void DCCTimer::DCCEXledcAttachPin(uint8_t pin, int8_t channel, bool inverted) {
|
||||||
|
DIAG(F("Attaching pin %d to channel %d %c"), pin, channel, inverted ? 'I' : ' ');
|
||||||
|
ledcAttachPin(pin, channel);
|
||||||
|
if (inverted) // we attach again but with inversion
|
||||||
|
gpio_matrix_out(pin, LEDCToMux[channel], inverted, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
void DCCTimer::DCCEXanalogCopyChannel(int8_t frompin, int8_t topin) {
|
||||||
|
// arguments are signed depending on inversion of pins
|
||||||
|
DIAG(F("Pin %d copied to %d"), frompin, topin);
|
||||||
|
bool inverted = false;
|
||||||
|
if (frompin<0)
|
||||||
|
frompin = -frompin;
|
||||||
|
if (topin<0) {
|
||||||
|
inverted = true;
|
||||||
|
topin = -topin;
|
||||||
|
}
|
||||||
|
int channel = pin_to_channel[frompin]; // after abs(frompin)
|
||||||
|
pin_to_channel[topin] = channel;
|
||||||
|
DCCTimer::DCCEXledcAttachPin(topin, channel, inverted);
|
||||||
|
}
|
||||||
|
|
||||||
|
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value, bool invert) {
|
||||||
|
// This allocates channels 15, 13, 11, ....
|
||||||
|
// so each channel gets its own timer.
|
||||||
if (pin < SOC_GPIO_PIN_COUNT) {
|
if (pin < 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;
|
||||||
}
|
}
|
||||||
pin_to_channel[pin] = --cnt_channel;
|
// search for free channels top down
|
||||||
ledcSetup(cnt_channel, 1000, 8);
|
for (search_channel=LEDC_CHANNELS-1; search_channel >=cnt_channel; search_channel -= 2) {
|
||||||
ledcAttachPin(pin, cnt_channel);
|
bool chanused = false;
|
||||||
|
for (n=0; n < SOC_GPIO_PIN_COUNT; n++) {
|
||||||
|
if (pin_to_channel[n] == search_channel) { // current search_channel used
|
||||||
|
chanused = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (chanused)
|
||||||
|
continue;
|
||||||
|
if (n == SOC_GPIO_PIN_COUNT) // current search_channel unused
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if (search_channel >= cnt_channel) {
|
||||||
|
pin_to_channel[pin] = search_channel;
|
||||||
|
DIAG(F("Pin %d assigned to search channel %d"), pin, search_channel);
|
||||||
|
} else {
|
||||||
|
pin_to_channel[pin] = --cnt_channel; // This sets 15, 13, ...
|
||||||
|
DIAG(F("Pin %d assigned to new channel %d"), pin, cnt_channel);
|
||||||
|
--cnt_channel; // Now we are at 14, 12, ...
|
||||||
|
}
|
||||||
|
ledcSetup(pin_to_channel[pin], 1000, 8);
|
||||||
|
DCCEXledcAttachPin(pin, pin_to_channel[pin], invert);
|
||||||
} else {
|
} else {
|
||||||
ledcAttachPin(pin, pin_to_channel[pin]);
|
// This else is only here so we can enable diag
|
||||||
|
// Pin should be already attached to channel
|
||||||
|
// DIAG(F("Pin %d assigned to old channel %d"), pin, pin_to_channel[pin]);
|
||||||
}
|
}
|
||||||
ledcWrite(pin_to_channel[pin], value);
|
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);
|
||||||
|
|
|
@ -333,7 +333,9 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
|
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value, bool invert) {
|
||||||
|
if (invert)
|
||||||
|
value = 255-value;
|
||||||
// Calculate percentage duty cycle from value given
|
// 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) {
|
||||||
|
|
26
EXRAIL2.cpp
26
EXRAIL2.cpp
|
@ -54,6 +54,7 @@
|
||||||
#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.
|
||||||
|
@ -176,7 +177,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;
|
||||||
|
@ -251,6 +252,12 @@ if (compileFeatures & FEATURE_SIGNAL) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
case OPCODE_ONSENSOR:
|
||||||
|
new EXRAILSensor(operand,progCounter+3,true );
|
||||||
|
break;
|
||||||
|
case OPCODE_ONBUTTON:
|
||||||
|
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);
|
||||||
|
@ -411,7 +418,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) {
|
||||||
|
@ -480,6 +487,7 @@ bool RMFT2::skipIfBlock() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void RMFT2::loop() {
|
void RMFT2::loop() {
|
||||||
|
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;
|
||||||
|
@ -1066,7 +1074,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
|
||||||
|
@ -1084,6 +1092,8 @@ 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
|
||||||
|
@ -1146,7 +1156,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
|
||||||
|
|
||||||
/* 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.
|
||||||
|
@ -1166,7 +1176,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
|
||||||
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=sigid & ~SIGNAL_ID_MASK;
|
VPIN sigtype=sigid & ~SIGNAL_ID_MASK;
|
||||||
|
|
||||||
|
@ -1174,7 +1184,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
|
||||||
// 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;
|
||||||
}
|
}
|
||||||
|
@ -1292,7 +1302,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("Looking for clock event at : %d"), clocktime);
|
DIAG(F("clockEvent 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);
|
||||||
|
@ -1302,7 +1312,7 @@ 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("Looking for Power event on track : %c"), track);
|
DIAG(F("powerEvent : %c"), track);
|
||||||
if (overload) {
|
if (overload) {
|
||||||
onOverloadLookup->handleEvent(F("POWER"),track);
|
onOverloadLookup->handleEvent(F("POWER"),track);
|
||||||
}
|
}
|
||||||
|
|
|
@ -73,7 +73,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,OPCODE_TOGGLE_TURNOUT,
|
||||||
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()
|
||||||
|
|
|
@ -114,6 +114,8 @@
|
||||||
#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
|
||||||
|
@ -279,6 +281,8 @@
|
||||||
#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)
|
||||||
|
|
|
@ -553,6 +553,8 @@ 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),
|
||||||
|
|
104
EXRAILSensor.cpp
Normal file
104
EXRAILSensor.cpp
Normal file
|
@ -0,0 +1,104 @@
|
||||||
|
/*
|
||||||
|
* © 2024 Chris Harlow
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* This file is part of CommandStation-EX
|
||||||
|
*
|
||||||
|
* This is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* It is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**********************************************************************
|
||||||
|
EXRAILSensor represents a sensor that should be monitored in order
|
||||||
|
to call an exrail ONBUTTON or ONCHANGE handler.
|
||||||
|
These are created at EXRAIL startup and thus need no delete or listing
|
||||||
|
capability.
|
||||||
|
The basic logic is similar to that found in the Sensor class
|
||||||
|
except that on the relevant change an EXRAIL thread is started.
|
||||||
|
**********************************************************************/
|
||||||
|
|
||||||
|
#include "EXRAILSensor.h"
|
||||||
|
#include "EXRAIL2.h"
|
||||||
|
|
||||||
|
void EXRAILSensor::checkAll() {
|
||||||
|
if (firstSensor == NULL) return; // No sensors to be scanned
|
||||||
|
if (readingSensor == NULL) {
|
||||||
|
// Not currently scanning sensor list
|
||||||
|
unsigned long thisTime = micros();
|
||||||
|
if (thisTime - lastReadCycle < cycleInterval) return;
|
||||||
|
// Required time has elapsed since last read cycle started,
|
||||||
|
// so initiate new scan through the sensor list
|
||||||
|
readingSensor = firstSensor;
|
||||||
|
lastReadCycle = thisTime;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Loop until either end of list is encountered or we pause for some reason
|
||||||
|
byte sensorCount = 0;
|
||||||
|
|
||||||
|
while (readingSensor != NULL) {
|
||||||
|
bool pause=readingSensor->check();
|
||||||
|
// Move to next sensor in list.
|
||||||
|
readingSensor = readingSensor->nextSensor;
|
||||||
|
// Currently process max of 16 sensors per entry.
|
||||||
|
// Performance measurements taken during development indicate that, with 128 sensors configured
|
||||||
|
// on 8x 16-pin MCP23017 GPIO expanders with polling (no change notification), all inputs can be read from the devices
|
||||||
|
// within 1.4ms (400Mhz I2C bus speed), and a full cycle of checking 128 sensors for changes takes under a millisecond.
|
||||||
|
if (pause || (++sensorCount)>=16) return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool EXRAILSensor::check() {
|
||||||
|
// check for debounced change in this sensor
|
||||||
|
inputState = IODevice::read(pin);
|
||||||
|
|
||||||
|
// Check if changed since last time, and process changes.
|
||||||
|
if (inputState == active) {// no change
|
||||||
|
latchDelay = minReadCount; // Reset counter
|
||||||
|
return false; // no change
|
||||||
|
}
|
||||||
|
|
||||||
|
// Change detected ... has it stayed changed for long enough
|
||||||
|
if (latchDelay > 0) {
|
||||||
|
latchDelay--;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// change validated, act on it.
|
||||||
|
active = inputState;
|
||||||
|
latchDelay = minReadCount; // Reset debounce counter
|
||||||
|
if (onChange || active) {
|
||||||
|
new RMFT2(progCounter);
|
||||||
|
return true; // Don't check any more sensors on this entry
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
EXRAILSensor::EXRAILSensor(VPIN _pin, int _progCounter, bool _onChange) {
|
||||||
|
// Add to the start of the list
|
||||||
|
//DIAG(F("ONthing vpin=%d at %d"), _pin, _progCounter);
|
||||||
|
nextSensor = firstSensor;
|
||||||
|
firstSensor = this;
|
||||||
|
|
||||||
|
pin=_pin;
|
||||||
|
progCounter=_progCounter;
|
||||||
|
onChange=_onChange;
|
||||||
|
|
||||||
|
IODevice::configureInput(pin, true);
|
||||||
|
active = IODevice::read(pin);
|
||||||
|
inputState = active;
|
||||||
|
latchDelay = minReadCount;
|
||||||
|
}
|
||||||
|
|
||||||
|
EXRAILSensor *EXRAILSensor::firstSensor=NULL;
|
||||||
|
EXRAILSensor *EXRAILSensor::readingSensor=NULL;
|
||||||
|
unsigned long EXRAILSensor::lastReadCycle=0;
|
50
EXRAILSensor.h
Normal file
50
EXRAILSensor.h
Normal file
|
@ -0,0 +1,50 @@
|
||||||
|
/*
|
||||||
|
* © 2024 Chris Harlow
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* This file is part of CommandStation-EX
|
||||||
|
*
|
||||||
|
* This is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* It is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef EXRAILSensor_h
|
||||||
|
#define EXRAILSensor_h
|
||||||
|
#include "IODevice.h"
|
||||||
|
class EXRAILSensor {
|
||||||
|
static EXRAILSensor * firstSensor;
|
||||||
|
static EXRAILSensor * readingSensor;
|
||||||
|
static unsigned long lastReadCycle;
|
||||||
|
|
||||||
|
public:
|
||||||
|
static void checkAll();
|
||||||
|
|
||||||
|
EXRAILSensor(VPIN _pin, int _progCounter, bool _onChange);
|
||||||
|
bool check();
|
||||||
|
|
||||||
|
private:
|
||||||
|
static const unsigned int cycleInterval = 10000; // min time between consecutive reads of each sensor in microsecs.
|
||||||
|
// should not be less than device scan cycle time.
|
||||||
|
static const byte minReadCount = 4; // number of additional scans before acting on change
|
||||||
|
// E.g. 1 means that a change is ignored for one scan and actioned on the next.
|
||||||
|
// Max value is 63
|
||||||
|
|
||||||
|
EXRAILSensor* nextSensor;
|
||||||
|
VPIN pin;
|
||||||
|
int progCounter;
|
||||||
|
bool active;
|
||||||
|
bool inputState;
|
||||||
|
bool onChange;
|
||||||
|
byte latchDelay;
|
||||||
|
};
|
||||||
|
#endif
|
|
@ -1 +1 @@
|
||||||
#define GITHUB_SHA "devel-202404012205Z"
|
#define GITHUB_SHA "devel-202404061747Z"
|
||||||
|
|
|
@ -1,7 +1,9 @@
|
||||||
/*
|
/*
|
||||||
* © 2023, Neil McKechnie. All rights reserved.
|
* © 2024, Paul Antoine
|
||||||
|
* © 2023, Neil McKechnie
|
||||||
|
* All rights reserved.
|
||||||
*
|
*
|
||||||
* This file is part of DCC++EX API
|
* This file is part of DCC-EX API
|
||||||
*
|
*
|
||||||
* This is free software: you can redistribute it and/or modify
|
* 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
|
||||||
|
@ -112,13 +114,14 @@ 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);
|
||||||
|
|
||||||
|
|
|
@ -336,8 +336,6 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/)
|
||||||
if (tSpeed <= 1) brake = 255;
|
if (tSpeed <= 1) brake = 255;
|
||||||
else if (tSpeed >= 127) brake = 0;
|
else if (tSpeed >= 127) brake = 0;
|
||||||
else brake = 2 * (128-tSpeed);
|
else brake = 2 * (128-tSpeed);
|
||||||
if (invertBrake)
|
|
||||||
brake=255-brake;
|
|
||||||
|
|
||||||
{ // new block because of variable f
|
{ // new block because of variable f
|
||||||
#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32)
|
#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32)
|
||||||
|
@ -349,12 +347,12 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
//DIAG(F("Brake pin %d freqency %d"), brakePin, f);
|
//DIAG(F("Brake pin %d value %d freqency %d"), brakePin, brake, f);
|
||||||
|
DCCTimer::DCCEXanalogWrite(brakePin, brake, invertBrake);
|
||||||
DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency
|
DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency
|
||||||
DCCTimer::DCCEXanalogWrite(brakePin,brake);
|
|
||||||
#else // all AVR here
|
#else // all AVR here
|
||||||
DCCTimer::DCCEXanalogWriteFrequency(brakePin, frequency); // frequency steps
|
DCCTimer::DCCEXanalogWriteFrequency(brakePin, frequency); // frequency steps
|
||||||
analogWrite(brakePin,brake);
|
analogWrite(brakePin, invertBrake ? 255-brake : brake);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -404,26 +402,26 @@ 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)))
|
if ( !(trackMode & (TRACK_MODE_MAIN | TRACK_MODE_PROG | TRACK_MODE_EXT | TRACK_MODE_BOOST)))
|
||||||
return;
|
return;
|
||||||
byte duty = on ? 207 : 0; // duty of 81% at 62500Hz this gives pauses of 3usec
|
byte duty = on ? 207 : 0; // duty of 81% at 62500Hz this gives pauses of 3usec
|
||||||
if (invertBrake)
|
|
||||||
duty = 255-duty;
|
|
||||||
#if defined(ARDUINO_ARCH_ESP32)
|
#if defined(ARDUINO_ARCH_ESP32)
|
||||||
if(on) {
|
if(on) {
|
||||||
DCCTimer::DCCEXanalogWrite(brakePin,duty);
|
DCCTimer::DCCEXInrushControlOn(brakePin, duty, invertBrake);
|
||||||
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max
|
|
||||||
} else {
|
} else {
|
||||||
ledcDetachPin(brakePin);
|
ledcDetachPin(brakePin); // not DCCTimer::DCCEXledcDetachPin() as we have not
|
||||||
|
// registered the pin in the pin to channel array
|
||||||
}
|
}
|
||||||
#elif defined(ARDUINO_ARCH_STM32)
|
#elif defined(ARDUINO_ARCH_STM32)
|
||||||
if(on) {
|
if(on) {
|
||||||
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max
|
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max
|
||||||
DCCTimer::DCCEXanalogWrite(brakePin,duty);
|
DCCTimer::DCCEXanalogWrite(brakePin,duty,invertBrake);
|
||||||
} else {
|
} else {
|
||||||
pinMode(brakePin, OUTPUT);
|
pinMode(brakePin, OUTPUT);
|
||||||
}
|
}
|
||||||
#else // all AVR here
|
#else // all AVR here
|
||||||
|
if (invertBrake)
|
||||||
|
duty = 255-duty;
|
||||||
if(on){
|
if(on){
|
||||||
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max
|
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max
|
||||||
}
|
}
|
||||||
|
|
|
@ -193,13 +193,14 @@ 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, uint8_t frequency=0);
|
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)
|
||||||
ledcDetachPin(brakePin);
|
DCCTimer::DCCEXledcDetachPin(brakePin);
|
||||||
#else
|
#else
|
||||||
setDCSignal(128);
|
setDCSignal(128);
|
||||||
#endif
|
#endif
|
||||||
|
|
98
Release_Notes/Exrail mods.txt
Normal file
98
Release_Notes/Exrail mods.txt
Normal file
|
@ -0,0 +1,98 @@
|
||||||
|
|
||||||
|
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
|
|
@ -38,8 +38,8 @@
|
||||||
if (track[t]->getMode()==findmode) \
|
if (track[t]->getMode()==findmode) \
|
||||||
track[t]->function;
|
track[t]->function;
|
||||||
|
|
||||||
MotorDriver * TrackManager::track[MAX_TRACKS];
|
MotorDriver * TrackManager::track[MAX_TRACKS] = { NULL };
|
||||||
int16_t TrackManager::trackDCAddr[MAX_TRACKS];
|
int16_t TrackManager::trackDCAddr[MAX_TRACKS] = { 0 };
|
||||||
|
|
||||||
int8_t TrackManager::lastTrack=-1;
|
int8_t TrackManager::lastTrack=-1;
|
||||||
bool TrackManager::progTrackSyncMain=false;
|
bool TrackManager::progTrackSyncMain=false;
|
||||||
|
@ -251,18 +251,47 @@ 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
|
||||||
|
|
|
@ -211,6 +211,19 @@ 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
|
||||||
|
|
|
@ -220,9 +220,15 @@
|
||||||
//
|
//
|
||||||
#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")
|
||||||
|
|
14
version.h
14
version.h
|
@ -3,7 +3,19 @@
|
||||||
|
|
||||||
#include "StringFormatter.h"
|
#include "StringFormatter.h"
|
||||||
|
|
||||||
#define VERSION "5.2.42"
|
#define VERSION "5.2.48"
|
||||||
|
// 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.42 - ESP32 Bugfix: Uninitialized stack variable
|
||||||
// 5.2.41 - Update rotary encoder default address to 0x67
|
// 5.2.41 - Update rotary encoder default address to 0x67
|
||||||
// 5.2.40 - Allow no shield
|
// 5.2.40 - Allow no shield
|
||||||
|
|
Loading…
Reference in New Issue
Block a user