Skip to content

Commit

Permalink
Merge branch 'devel' into devel_chris
Browse files Browse the repository at this point in the history
  • Loading branch information
Asbelos committed Apr 12, 2024
2 parents 132e2d0 + 91e60b3 commit 3fc90c9
Show file tree
Hide file tree
Showing 18 changed files with 297 additions and 44 deletions.
76 changes: 73 additions & 3 deletions DCC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Die Adresse für den ersten erweiterten Zubehördecoder ist wie bei den einfachen
Zubehördecodern die Adresse 4 = 1000-0001 0111-0001 . Diese Adresse wird in
Die Adresse f�r den ersten erweiterten Zubeh�rdecoder ist wie bei den einfachen
Zubeh�rdecodern die Adresse 4 = 1000-0001 0111-0001 . Diese Adresse wird in
Anwenderdialogen als Adresse 1 dargestellt.
This means that the first address shown to the user as "1" is mapped
Expand Down Expand Up @@ -500,6 +500,36 @@ const ackOp FLASH READ_CV_PROG[] = {

const ackOp FLASH LOCO_ID_PROG[] = {
BASELINE,
// first check cv20 for extended addressing
SETCV, (ackOp)20, // CV 19 is extended
SETBYTE, (ackOp)0,
VB, WACK, ITSKIP, // skip past extended section if cv20 is zero
// read cv20 and 19 and merge
STARTMERGE, // Setup to read cv 20
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
VB, WACK, NAKSKIP, // bad read of cv20, assume its 0
STASHLOCOID, // keep cv 20 until we have cv19 as well.
SETCV, (ackOp)19,
STARTMERGE, // Setup to read cv 19
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
VB, WACK, NAKFAIL, // cant recover if cv 19 unreadable
COMBINE1920, // Combile byte with stash and callback
// end of advanced 20,19 check
SKIPTARGET,
SETCV, (ackOp)19, // CV 19 is consist setting
SETBYTE, (ackOp)0,
VB, WACK, ITSKIP, // ignore consist if cv19 is zero (no consist)
Expand Down Expand Up @@ -566,6 +596,10 @@ const ackOp FLASH LOCO_ID_PROG[] = {

const ackOp FLASH SHORT_LOCO_ID_PROG[] = {
BASELINE,
// Clear consist CV 19,20
SETCV,(ackOp)20,
SETBYTE, (ackOp)0,
WB,WACK, // ignore dedcoder without cv20 support
SETCV,(ackOp)19,
SETBYTE, (ackOp)0,
WB,WACK, // ignore dedcoder without cv19 support
Expand All @@ -581,9 +615,25 @@ const ackOp FLASH SHORT_LOCO_ID_PROG[] = {
CALLFAIL
};

// for CONSIST_ID_PROG the 20,19 values are already calculated
const ackOp FLASH CONSIST_ID_PROG[] = {
BASELINE,
SETCV,(ackOp)20,
SETBYTEH, // high byte to CV 20
WB,WACK, // ignore dedcoder without cv20 support
SETCV,(ackOp)19,
SETBYTEL, // low byte of word
WB,WACK,ITC1, // If ACK, we are done - callback(1) means Ok
VB,WACK,ITC1, // Some decoders do not ack and need verify
CALLFAIL
};

const ackOp FLASH LONG_LOCO_ID_PROG[] = {
BASELINE,
// Clear consist CV 19
// Clear consist CV 19,20
SETCV,(ackOp)20,
SETBYTE, (ackOp)0,
WB,WACK, // ignore dedcoder without cv20 support
SETCV,(ackOp)19,
SETBYTE, (ackOp)0,
WB,WACK, // ignore decoder without cv19 support
Expand Down Expand Up @@ -652,6 +702,26 @@ void DCC::setLocoId(int id,ACK_CALLBACK callback) {
DCCACK::Setup(id | 0xc000,LONG_LOCO_ID_PROG, callback);
}

void DCC::setConsistId(int id,bool reverse,ACK_CALLBACK callback) {
if (id<0 || id>10239) { //0x27FF according to standard
callback(-1);
return;
}
byte cv20;
byte cv19;

if (id<=HIGHEST_SHORT_ADDR) {
cv19=id;
cv20=0;
}
else {
cv20=id/100;
cv19=id%100;
}
if (reverse) cv19|=0x80;
DCCACK::Setup((cv20<<8)|cv19, CONSIST_ID_PROG, callback);
}

void DCC::forgetLoco(int cab) { // removes any speed reminders for this loco
setThrottle2(cab,1); // ESTOP this loco if still on track
int reg=lookupSpeedTable(cab, false);
Expand Down
2 changes: 1 addition & 1 deletion DCC.h
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ class DCC

static void getLocoId(ACK_CALLBACK callback);
static void setLocoId(int id,ACK_CALLBACK callback);

static void setConsistId(int id,bool reverse,ACK_CALLBACK callback);
// Enhanced API functions
static void forgetLoco(int cab); // removes any speed reminders for this loco
static void forgetAllLocos(); // removes all speed reminders
Expand Down
17 changes: 17 additions & 0 deletions DCCACK.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -314,6 +314,14 @@ void DCCACK::loop() {
callback( LONG_ADDR_MARKER | ( ackManagerByte + ((ackManagerStash - 192) << 8)));
return;

case COMBINE1920:
// ackManagerStash is cv20, ackManagerByte is CV 19
// This will not be called if cv20==0
ackManagerByte &= 0x7F; // ignore direction marker
ackManagerByte %=100; // take last 2 decimal digits
callback( ackManagerStash*100+ackManagerByte);
return;

case ITSKIP:
if (!ackReceived) break;
// SKIP opcodes until SKIPTARGET found
Expand All @@ -322,6 +330,15 @@ void DCCACK::loop() {
opcode=GETFLASH(ackManagerProg);
}
break;

case NAKSKIP:
if (ackReceived) break;
// SKIP opcodes until SKIPTARGET found
while (opcode!=SKIPTARGET) {
ackManagerProg++;
opcode=GETFLASH(ackManagerProg);
}
break;
case SKIPTARGET:
break;
default:
Expand Down
2 changes: 2 additions & 0 deletions DCCACK.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,8 @@ enum ackOp : byte
STASHLOCOID, // keeps current byte value for later
COMBINELOCOID, // combines current value with stashed value and returns it
ITSKIP, // skip to SKIPTARGET if ack true
NAKSKIP, // skip to SKIPTARGET if ack false
COMBINE1920, // combine cvs 19 and 20 and callback
SKIPTARGET = 0xFF // jump to target
};

Expand Down
11 changes: 11 additions & 0 deletions DCCEXParser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -458,6 +458,9 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
DCC::setLocoId(p[0],callback_Wloco);
else if (params == 4) // WRITE CV ON PROG <W CV VALUE [CALLBACKNUM] [CALLBACKSUB]>
DCC::writeCVByte(p[0], p[1], callback_W4);
else if ((params==2 || params==3 ) && p[0]=="CONSIST"_hk ) {
DCC::setConsistId(p[1],p[2]=="REVERSE"_hk,callback_Wconsist);
}
else if (params == 2) // WRITE CV ON PROG <W CV VALUE>
DCC::writeCVByte(p[0], p[1], callback_W);
else
Expand Down Expand Up @@ -1348,3 +1351,11 @@ void DCCEXParser::callback_Wloco(int16_t result)
StringFormatter::send(getAsyncReplyStream(), F("<w %d>\n"), result);
commitAsyncReplyStream();
}

void DCCEXParser::callback_Wconsist(int16_t result)
{
if (result==1) result=stashP[1]; // pick up original requested id from command
StringFormatter::send(getAsyncReplyStream(), F("<w CONSIST %d%S>\n"),
result, stashP[2]=="REVERSE"_hk ? F(" REVERSE") : F(""));
commitAsyncReplyStream();
}
1 change: 1 addition & 0 deletions DCCEXParser.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,7 @@ struct DCCEXParser
static void callback_R(int16_t result);
static void callback_Rloco(int16_t result);
static void callback_Wloco(int16_t result);
static void callback_Wconsist(int16_t result);
static void callback_Vbit(int16_t result);
static void callback_Vbyte(int16_t result);
static FILTER_CALLBACK filterCallback;
Expand Down
6 changes: 5 additions & 1 deletion DCCTimer.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,11 @@ class DCCTimer {
static void startRailcomTimer(byte brakePin);
static void ackRailcomTimer();
static void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency);
static void DCCEXanalogWrite(uint8_t pin, int value);
static void DCCEXanalogWrite(uint8_t pin, int value, bool invert);
static void DCCEXledcDetachPin(uint8_t pin);
static void DCCEXanalogCopyChannel(int8_t frompin, int8_t topin);
static void DCCEXInrushControlOn(uint8_t pin, int duty, bool invert);
static void DCCEXledcAttachPin(uint8_t pin, int8_t channel, bool inverted);

// Update low ram level. Allow for extra bytes to be specified
// by estimation or inspection, that may be used by other
Expand Down
96 changes: 90 additions & 6 deletions DCCTimerESP.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,7 @@ int DCCTimer::freeMemory() {
////////////////////////////////////////////////////////////////////////

#ifdef ARDUINO_ARCH_ESP32
#include "DIAG.h"
#include <driver/adc.h>
#include <soc/sens_reg.h>
#include <soc/sens_struct.h>
Expand Down Expand Up @@ -154,8 +155,10 @@ void DCCTimer::reset() {
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
if (f >= 16)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f);
else if (f == 7)
/*
else if (f == 7) // not used on ESP32
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 62500);
*/
else if (f >= 4)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 32000);
else if (f >= 3)
Expand Down Expand Up @@ -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_to_channel[pin] == 0) {
int search_channel;
int n;
if (!cnt_channel) {
log_e("No more PWM channels available! All %u already used", LEDC_CHANNELS);
return;
}
pin_to_channel[pin] = --cnt_channel;
ledcSetup(cnt_channel, 1000, 8);
ledcAttachPin(pin, cnt_channel);
// search for free channels top down
for (search_channel=LEDC_CHANNELS-1; search_channel >=cnt_channel; search_channel -= 2) {
bool chanused = false;
for (n=0; n < SOC_GPIO_PIN_COUNT; n++) {
if (pin_to_channel[n] == search_channel) { // current search_channel used
chanused = true;
break;
}
}
if (chanused)
continue;
if (n == SOC_GPIO_PIN_COUNT) // current search_channel unused
break;
}
if (search_channel >= cnt_channel) {
pin_to_channel[pin] = search_channel;
DIAG(F("Pin %d assigned to search channel %d"), pin, search_channel);
} else {
pin_to_channel[pin] = --cnt_channel; // This sets 15, 13, ...
DIAG(F("Pin %d assigned to new channel %d"), pin, cnt_channel);
--cnt_channel; // Now we are at 14, 12, ...
}
ledcSetup(pin_to_channel[pin], 1000, 8);
DCCEXledcAttachPin(pin, pin_to_channel[pin], invert);
} else {
ledcAttachPin(pin, pin_to_channel[pin]);
// This else is only here so we can enable diag
// Pin should be already attached to channel
// DIAG(F("Pin %d assigned to old channel %d"), pin, pin_to_channel[pin]);
}
ledcWrite(pin_to_channel[pin], value);
}
}

void DCCTimer::DCCEXInrushControlOn(uint8_t pin, int duty, bool inverted) {
// this uses hardcoded channel 0
ledcSetup(0, 62500, 8);
DCCEXledcAttachPin(pin, 0, inverted);
ledcWrite(0, duty);
}

int ADCee::init(uint8_t pin) {
pinMode(pin, ANALOG);
adc1_config_width(ADC_WIDTH_BIT_12);
Expand Down
4 changes: 3 additions & 1 deletion DCCTimerSTM32.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -333,7 +333,9 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency
return;
}

void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value, bool invert) {
if (invert)
value = 255-value;
// Calculate percentage duty cycle from value given
uint32_t duty_cycle = (value * 100 / 256) + 1;
if (pin_timer[pin] != NULL) {
Expand Down
Loading

0 comments on commit 3fc90c9

Please sign in to comment.