1
0
mirror of https://github.com/DCC-EX/CommandStation-EX.git synced 2025-04-03 20:20:12 +02:00

Compare commits

..

14 Commits

Author SHA1 Message Date
Asbelos
4125e73318 Fix CLEAR_ALL_STASH 2025-03-29 10:33:36 +00:00
Harald Barth
911bbd63be version 5.4.6 2025-02-25 00:02:06 +01:00
Harald Barth
393b0bbd16 Bugfix: Do not drop further commands in same packet 2025-02-24 23:57:56 +01:00
Harald Barth
d9bd1e75f2 sort power output different 2025-02-21 00:09:35 +01:00
Harald Barth
d1daf41f12 version 5.4.5 2025-02-20 21:21:41 +01:00
Harald Barth
6bfa7028c4 Merge branch 'master' of https://github.com/DCC-EX/CommandStation-EX 2025-02-20 21:20:44 +01:00
Harald Barth
a5d1d04882 remove unneccessary warning about prog track as it can happen normally 2025-02-20 21:18:10 +01:00
Harald Barth
bd6e426499 track power is always turned on after setJoin() not by setJoin() 2025-02-20 21:16:50 +01:00
Harald Barth
09bae44cc0 ESP32: Better detection of wrong IDF version 2025-02-20 21:15:49 +01:00
Fred
9f3354c687
Move xls release notes to release notes folder (#440) 2025-02-18 09:23:30 -05:00
Fred
fb495985f4
Add XLS searchable version of 5.4 release notes (#439) 2025-02-18 08:30:28 -05:00
Harald Barth
f868604ca9 version 5.4.4 2025-01-31 11:22:55 +01:00
Harald Barth
41168a9dd8 Bugfix: trailing > in command was not replaced with \0 which did break <+> commands 2025-01-31 11:19:22 +01:00
Harald Barth
0154e7fd78 Bugfix: serial COMMAND_BUFFER_SIZE could be silently overrun 2025-01-31 11:17:59 +01:00
59 changed files with 598 additions and 3453 deletions

View File

@ -1,57 +1,31 @@
/*
* © 2023-2025, Barry Daniel
* © 2025 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/>.
*/
//sensorCAM parser.cpp version 3.06 Jan 2025
#include "DCCEXParser.h"
//sensorCAM parser.cpp version 3.03 Sep 2024
#include "CamParser.h"
#include "FSH.h"
#include "IO_EXSensorCAM.h"
#ifndef SENSORCAM_VPIN //define CAM vpin (700?) in config.h
#define SENSORCAM_VPIN 0
#endif
#define CAM_VPIN SENSORCAM_VPIN
#ifndef SENSORCAM2_VPIN
#define SENSORCAM2_VPIN CAM_VPIN
#endif
#ifndef SENSORCAM3_VPIN
#define SENSORCAM3_VPIN 0
#endif
const int CAMVPINS[] = {CAM_VPIN,SENSORCAM_VPIN,SENSORCAM2_VPIN,SENSORCAM3_VPIN};
const int16_t ver=30177;
const int16_t ve =2899;
VPIN EXSensorCAM::CAMBaseVpin = CAM_VPIN;
// The CAMVPINS array will be filled by IO_EXSensorCam HAL drivers calling
// the CamParser::addVpin() function.
// The CAMBaseVpin is the one to be used when commands are given without a vpin.
VPIN CamParser::CAMBaseVpin = 0; // no vpins yet known
VPIN CamParser::CAMVPINS[] = {0,0,0,0}; // determines max # CAM's
int CamParser::vpcount=sizeof(CAMVPINS)/sizeof(CAMVPINS[0]);
void CamParser::parse(Print * stream, byte & opcode, byte & paramCount, int16_t p[]) {
if (opcode!='N') return; // this is not for us.
if (parseN(stream,paramCount,p)) opcode=0; // we have consumed this
// If we fail, the caller will <X> the <N command.
}
bool CamParser::parseN(Print * stream, byte paramCount, int16_t p[]) {
(void)stream; // probably unused parameter
if (CAMBaseVpin==0) CAMBaseVpin=CAMVPINS[0]; // default to CAM 1.
VPIN vpin=CAMBaseVpin; //use current CAM selection
(void)stream; // probably unused parameter
VPIN vpin=EXSensorCAM::CAMBaseVpin; //use current CAM selection
if (paramCount==0) {
DIAG(F("Cam base vpin:%d"),CAMBaseVpin);
for (auto i=0;i<vpcount;i++){
if (CAMVPINS[i]==0) break;
DIAG(F("EXSensorCam #%d vpin %d"),i+1,CAMVPINS[i]);
}
DIAG(F("vpin:%d EXSensorCAMs defined at Vpins #1@ %d #2@ %d #3@ %d"),vpin,CAMVPINS[1],CAMVPINS[2],CAMVPINS[3]);
return true;
}
uint8_t camop=p[0]; // cam oprerator
@ -59,45 +33,44 @@ bool CamParser::parseN(Print * stream, byte paramCount, int16_t p[]) {
int16_t param3=9999; // =0 could invoke parameter changes. & -1 gives later errors
if(camop=='C'){
if(p[1]>=100) CAMBaseVpin=p[1];
if(p[1]<=vpcount && p[1]>0) CAMBaseVpin=CAMVPINS[p[1]-1];
DIAG(F("CAM base Vpin: %c %d "),p[0],CAMBaseVpin);
if(p[1]>=100) EXSensorCAM::CAMBaseVpin=p[1];
if(p[1]<4) EXSensorCAM::CAMBaseVpin=CAMVPINS[p[1]];
DIAG(F("CAM base Vpin: %c %d "),p[0],EXSensorCAM::CAMBaseVpin);
return true;
}
if (camop<100) { //switch CAM# if p[1] dictates
if(p[1]>=100 && p[1]<=(vpcount*100+99)) { //limits to CAM# 1 to 4 for now
vpin=CAMVPINS[p[1]/100-1];
CAMBaseVpin=vpin;
if(p[1]>=100 && p[1]<400) { //limits to CAM# 1 to 3 for now
vpin=CAMVPINS[p[1]/100];
EXSensorCAM::CAMBaseVpin=vpin;
DIAG(F("switching to CAM %d baseVpin:%d"),p[1]/100,vpin);
p[1]=p[1]%100; //strip off CAM #
}
}
if (CAMBaseVpin==0) {DIAG(F("<n Error: Invalid CAM selected, default to CAM1>"));
return false; // cam not defined
}
if (EXSensorCAM::CAMBaseVpin==0) return false; // no cam defined
// send UPPER case to sensorCAM to flag binary data from a DCCEX-CS parser
switch(paramCount) {
case 1: //<N ver> produces '^'
if((camop == 'V') || (p[0] == ve) || (p[0] == ver) ) camop='^';
if((p[0] == ve) || (p[0] == ver) || (p[0] == 'V')) camop='^';
if (STRCHR_P((const char *)F("EFGMQRVW^"),camop) == nullptr) return false;
if (camop=='Q') param3=10; //<NQ> for activation state of all 10 banks of sensors
if (camop=='F') camop=']'; //<NF> for Reset/Finish webCAM.
break; // F Coded as ']' else conflicts with <Nf %%>
case 2: //<N camop p1>
if (STRCHR_P((const char *)F("ABFHILMNOPQRSTUV"),camop)==nullptr) return false;
if (STRCHR_P((const char *)F("ABFILMNOPQRSTUV"),camop)==nullptr) return false;
param1=p[1];
break;
case 3: //<N vpin rowY colx > or <N cmd p1 p2>
camop=p[0];
if (p[0]>=100) { //vpin - i.e. NOT 'A' through 'Z'
if (p[1]>236 || p[1]<0) return false; //row
if (p[2]>316 || p[2]<0) return false; //column
camop=0x80; // special 'a' case for IO_SensorCAM
vpin = p[0];
}else if (STRCHR_P((const char *)F("IJMNT"),camop) == nullptr) return false;
camop=p[0];
param1 = p[1];
param3 = p[2];
break;
@ -119,23 +92,4 @@ bool CamParser::parseN(Print * stream, byte paramCount, int16_t p[]) {
DIAG(F("CamParser: %d %c %d %d"),vpin,camop,param1,param3);
IODevice::writeAnalogue(vpin,param1,camop,param3);
return true;
}
void CamParser::addVpin(VPIN pin) {
// called by IO_EXSensorCam starting up a camera on a vpin
byte slot=255;
for (auto i=0;i<vpcount && slot==255;i++) {
if (CAMVPINS[i]==0) {
slot=i;
CAMVPINS[slot]=pin;
}
}
if (slot==255) {
DIAG(F("No more than %d cameras supported"),vpcount);
return;
}
if (slot==0) CAMBaseVpin=pin;
DIAG(F("CamParser Registered cam #%dvpin %d"),slot+1,pin);
// tell the DCCEXParser that we wish to filter commands
DCCEXParser::setCamParserFilter(&parse);
}

View File

@ -1,25 +1,3 @@
/*
* © 2023-2025, Barry Daniel
* © 2025 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 CamParser_H
#define CamParser_H
#include <Arduino.h>
@ -27,13 +5,7 @@
class CamParser {
public:
static void parse(Print * stream, byte & opcode, byte & paramCount, int16_t p[]);
static void addVpin(VPIN pin);
private:
static bool parseN(Print * stream, byte paramCount, int16_t p[]);
static VPIN CAMBaseVpin;
static VPIN CAMVPINS[];
static int vpcount;
static bool parseN(Print * stream, byte paramCount, int16_t p[]);
};

View File

@ -1,6 +1,6 @@
/*
* © 2022 Harald Barth
* © 2020-2025 Chris Harlow
* © 2020-2021 Chris Harlow
* © 2020 Gregor Baues
* © 2022 Colin Murdoch
* All rights reserved.
@ -31,7 +31,6 @@
#include "DCC.h"
#include "TrackManager.h"
#include "StringFormatter.h"
#include "Websockets.h"
// variables to hold clock time
int16_t lastclocktime;
@ -45,7 +44,6 @@ template<typename... Targs> void CommandDistributor::broadcastReply(clientType t
broadcastBufferWriter->flush();
StringFormatter::send(broadcastBufferWriter, msg...);
broadcastToClients(type);
if (type==COMMAND_TYPE) broadcastToClients(WEBSOCKET_TYPE);
}
#else
// on a single USB connection config, write direct to Serial and ignore flush/shove
@ -58,17 +56,14 @@ template<typename... Targs> void CommandDistributor::broadcastReply(clientType t
#ifdef CD_HANDLE_RING
// wifi or ethernet ring streams with multiple client types
RingStream * CommandDistributor::ring=0;
CommandDistributor::clientType CommandDistributor::clients[MAX_NUM_TCP_CLIENTS]={ NONE_TYPE }; // 0 is and must be NONE_TYPE
CommandDistributor::clientType CommandDistributor::clients[8]={
NONE_TYPE,NONE_TYPE,NONE_TYPE,NONE_TYPE,NONE_TYPE,NONE_TYPE,NONE_TYPE,NONE_TYPE};
// Parse is called by Withrottle or Ethernet interface to determine which
// protocol the client is using and call the appropriate part of dcc++Ex
void CommandDistributor::parse(byte clientId,byte * buffer, RingStream * stream) {
if (clientId>=sizeof (clients)) {
// Caution, diag dump of buffer could corrupt ringstream
// if headed by websocket bytes.
DIAG(F("::parse invalid client=%d"),clientId);
return;
}
if (Diag::WIFI && Diag::CMD)
DIAG(F("Parse C=%d T=%d B=%s"),clientId, clients[clientId], buffer);
ring=stream;
// First check if the client is not known
@ -77,40 +72,22 @@ void CommandDistributor::parse(byte clientId,byte * buffer, RingStream * stream
// client is using the DCC++ protocol where all commands start
// with '<'
if (clients[clientId] == NONE_TYPE) {
auto websock=Websockets::checkConnectionString(clientId,buffer,stream);
if (websock) {
clients[clientId]=WEBSOCK_CONNECTING_TYPE;
// websockets will have replied already
return;
}
if (buffer[0] == '<')
clients[clientId]=COMMAND_TYPE;
else
clients[clientId]=WITHROTTLE_TYPE;
}
// after first inbound transmission the websocket is connected
if (clients[clientId]==WEBSOCK_CONNECTING_TYPE)
clients[clientId]=WEBSOCKET_TYPE;
// mark buffer that is sent to parser
ring->mark(clientId);
// When type is known, send the string
// to the right parser
if (clients[clientId] == COMMAND_TYPE) {
ring->mark(clientId);
DCCEXParser::parse(stream, buffer, ring);
} else if (clients[clientId] == WITHROTTLE_TYPE) {
ring->mark(clientId);
WiThrottle::getThrottle(clientId)->parse(ring, buffer);
}
else if (clients[clientId] == WEBSOCKET_TYPE) {
buffer=Websockets::unmask(clientId,ring, buffer);
if (!buffer) return; // unmask may have handled it alrerday (ping/pong)
// mark ring with client flagged as websocket for transmission later
ring->mark(clientId | Websockets::WEBSOCK_CLIENT_MARKER);
DCCEXParser::parse(stream, buffer, ring);
}
if (ring->peekTargetMark()!=RingStream::NO_CLIENT) {
// The commit call will either write the length bytes
@ -154,7 +131,7 @@ void CommandDistributor::broadcastToClients(clientType type) {
for (byte clientId=0; clientId<sizeof(clients); clientId++) {
if (clients[clientId]==type) {
//DIAG(F("CD mark client %d"), clientId);
ring->mark(clientId | (type==WEBSOCKET_TYPE? Websockets::WEBSOCK_CLIENT_MARKER : 0));
ring->mark(clientId);
ring->print(broadcastBufferWriter->getString());
//DIAG(F("CD commit client %d"), clientId);
ring->commit();
@ -208,15 +185,10 @@ void CommandDistributor::setClockTime(int16_t clocktime, int8_t clockrate, byte
{
case 1:
if (clocktime != lastclocktime){
auto difference = clocktime - lastclocktime;
if (difference<0) difference+=1440;
DCC::setTime(clocktime,clockrate,difference>2);
// CAH. DIAG removed because LCD does it anyway.
LCD(6,F("Clk Time:%d Sp %d"), clocktime, clockrate);
// look for an event for this time
#ifdef EXRAIL_ACTIVE
RMFT2::clockEvent(clocktime,1);
#endif
// Now tell everyone else what the time is.
CommandDistributor::broadcastClockTime(clocktime, clockrate);
lastclocktime = clocktime;
@ -235,13 +207,9 @@ int16_t CommandDistributor::retClockTime() {
return lastclocktime;
}
void CommandDistributor::broadcastLoco(DCC::LOCO* sp) {
if (!sp) {
broadcastReply(COMMAND_TYPE,F("<l 0 -1 128 0>\n"));
return;
}
broadcastReply(COMMAND_TYPE, F("<l %d 0 %d %l>\n"),
sp->loco,sp->targetSpeed,sp->functions);
void CommandDistributor::broadcastLoco(byte slot) {
DCC::LOCO * sp=&DCC::speedTable[slot];
broadcastReply(COMMAND_TYPE, F("<l %d %d %d %l>\n"), sp->loco,slot,sp->speedCode,sp->functions);
#ifdef SABERTOOTH
if (Serial2 && sp->loco == SABERTOOTH) {
static uint8_t rampingmode = 0;
@ -312,6 +280,9 @@ void CommandDistributor::broadcastPower() {
state = '1';
}
if (state != '2')
broadcastReply(COMMAND_TYPE, F("<p%c>\n"),state);
// additional info about MAIN, PROG and JOIN
bool main=TrackManager::getMainPower()==POWERMODE::ON;
bool prog=TrackManager::getProgPower()==POWERMODE::ON;
@ -320,7 +291,7 @@ void CommandDistributor::broadcastPower() {
const FSH * reason=F("");
if (join) {
reason = F(" JOIN"); // with space at start so we can append without space
broadcastReply(COMMAND_TYPE, F("<p1 %S>\n"),reason);
broadcastReply(COMMAND_TYPE, F("<p1%S>\n"),reason);
} else {
if (main) {
//reason = F("MAIN");
@ -331,9 +302,6 @@ void CommandDistributor::broadcastPower() {
broadcastReply(COMMAND_TYPE, F("<p1 PROG>\n"));
}
}
if (state != '2')
broadcastReply(COMMAND_TYPE, F("<p%c>\n"),state);
#ifdef CD_HANDLE_RING
// send '1' if all main are on, otherwise global state (which in that case is '0' or '2')
broadcastReply(WITHROTTLE_TYPE, F("PPA%c\n"), main?'1': state);

View File

@ -1,6 +1,6 @@
/*
* © 2022 Harald Barth
* © 2020-2025 Chris Harlow
* © 2020-2021 Chris Harlow
* © 2020 Gregor Baues
* © 2022 Colin Murdoch
*
@ -28,7 +28,6 @@
#include "StringBuffer.h"
#include "defines.h"
#include "EXRAIL2.h"
#include "DCC.h"
#if WIFI_ON | ETHERNET_ON
// Command Distributor must handle a RingStream of clients
@ -37,17 +36,17 @@
class CommandDistributor {
public:
enum clientType: byte {NONE_TYPE = 0,COMMAND_TYPE,WITHROTTLE_TYPE,WEBSOCK_CONNECTING_TYPE,WEBSOCKET_TYPE}; // independent of other types, NONE_TYPE must be 0
enum clientType: byte {NONE_TYPE,COMMAND_TYPE,WITHROTTLE_TYPE};
private:
static void broadcastToClients(clientType type);
static StringBuffer * broadcastBufferWriter;
#ifdef CD_HANDLE_RING
static RingStream * ring;
static clientType clients[MAX_NUM_TCP_CLIENTS];
static clientType clients[8];
#endif
public :
static void parse(byte clientId,byte* buffer, RingStream * ring);
static void broadcastLoco(DCC::LOCO * slot);
static void broadcastLoco(byte slot);
static void broadcastForgetLoco(int16_t loco);
static void broadcastSensor(int16_t id, bool value);
static void broadcastTurnout(int16_t id, bool isClosed);

455
DCC.cpp
View File

@ -5,7 +5,7 @@
* © 2021 Herb Morton
* © 2020-2022 Harald Barth
* © 2020-2021 M Steve Todd
* © 2020-2025 Chris Harlow
* © 2020-2021 Chris Harlow
* All rights reserved.
*
* This file is part of DCC-EX
@ -37,8 +37,6 @@
#include "CommandDistributor.h"
#include "TrackManager.h"
#include "DCCTimer.h"
#include "Railcom.h"
#include "DCCQueue.h"
// This module is responsible for converting API calls into
// messages to be sent to the waveform generator.
@ -62,8 +60,6 @@ const byte FN_GROUP_5=0x10;
FSH* DCC::shieldName=NULL;
byte DCC::globalSpeedsteps=128;
#define SLOTLOOP for (auto slot=&speedTable[0];slot!=&speedTable[MAX_LOCOS];slot++)
void DCC::begin() {
StringFormatter::send(&USB_SERIAL,F("<iDCC-EX V-%S / %S / %S G-%S>\n"), F(VERSION), F(ARDUINO_TYPE), shieldName, F(GITHUB_SHA));
#ifndef DISABLE_EEPROM
@ -76,49 +72,13 @@ void DCC::begin() {
#endif
}
byte DCC::defaultMomentumA=0;
byte DCC::defaultMomentumD=0;
bool DCC::linearAcceleration=false;
byte DCC::getMomentum(LOCO * slot) {
auto target=slot->targetSpeed & 0x7f;
auto current=slot->speedCode & 0x7f;
if (target > current) {
// accelerating
auto momentum=slot->momentumA==MOMENTUM_USE_DEFAULT ? defaultMomentumA : slot->momentumA;
// if nonlinear acceleration, momentum is reduced according to
// gap between throttle and speed.
// ie. Loco takes accelerates faster if high throttle
if (momentum==0 || linearAcceleration) return momentum;
auto powerDifference= (target-current)/8;
if (momentum-powerDifference <0) return 0;
return momentum-powerDifference;
}
return slot->momentumD==MOMENTUM_USE_DEFAULT ? defaultMomentumD : slot->momentumD;
}
void DCC::setThrottle( uint16_t cab, uint8_t tSpeed, bool tDirection) {
if (tSpeed==1) {
if (cab==0) {
estopAll(); // ESTOP broadcast fix
return;
}
}
byte speedCode = (tSpeed & 0x7F) + tDirection * 128;
LOCO * slot=lookupSpeedTable(cab);
if (slot->targetSpeed==speedCode) return;
slot->targetSpeed=speedCode;
byte momentum=getMomentum(slot);
if (momentum && tSpeed!=1) { // not ESTOP
// we dont throttle speed, we just let the reminders take it to target
slot->momentum_base=millis();
}
else { // Momentum not involved, throttle now.
slot->speedCode = speedCode;
setThrottle2(cab, speedCode);
TrackManager::setDCSignal(cab,speedCode); // in case this is a dcc track on this addr
}
CommandDistributor::broadcastLoco(slot);
setThrottle2(cab, speedCode);
TrackManager::setDCSignal(cab,speedCode); // in case this is a dcc track on this addr
// retain speed for loco reminders
updateLocoReminder(cab, speedCode );
}
void DCC::setThrottle2( uint16_t cab, byte speedCode) {
@ -158,8 +118,8 @@ void DCC::setThrottle2( uint16_t cab, byte speedCode) {
b[nB++] = speedCode; // for encoding see setThrottle
}
if ((speedCode & 0x7F) == 1) DCCQueue::scheduleEstopPacket(b, nB, 4, cab); // highest priority
else DCCQueue::scheduleDCCSpeedPacket( b, nB, 4, cab);
DCCWaveform::mainTrack.schedulePacket(b, nB, 0);
}
void DCC::setFunctionInternal(int cab, byte byte1, byte byte2, byte count) {
@ -173,28 +133,24 @@ void DCC::setFunctionInternal(int cab, byte byte1, byte byte2, byte count) {
if (byte1!=0) b[nB++] = byte1;
b[nB++] = byte2;
DCCQueue::scheduleDCCPacket(b, nB, count);
DCCWaveform::mainTrack.schedulePacket(b, nB, count);
}
// returns speed steps 0 to 127 (1 == emergency stop)
// or -1 on "loco not found"
int8_t DCC::getThrottleSpeed(int cab) {
return getThrottleSpeedByte(cab) & 0x7F;
int reg=lookupSpeedTable(cab);
if (reg<0) return -1;
return speedTable[reg].speedCode & 0x7F;
}
// returns speed code byte
// or 128 (speed 0, dir forward) on "loco not found".
// This is the throttle set speed
uint8_t DCC::getThrottleSpeedByte(int cab) {
LOCO * slot=lookupSpeedTable(cab,false);
return slot?slot->targetSpeed:128;
}
// returns speed code byte for loco.
// This is the most recently send DCC speed packet byte
// or 128 (speed 0, dir forward) on "loco not found".
uint8_t DCC::getLocoSpeedByte(int cab) {
LOCO* slot=lookupSpeedTable(cab,false);
return slot?slot->speedCode:128;
int reg=lookupSpeedTable(cab);
if (reg<0)
return 128;
return speedTable[reg].speedCode;
}
// returns 0 to 7 for frequency
@ -203,11 +159,12 @@ uint8_t DCC::getThrottleFrequency(int cab) {
(void)cab;
return 0;
#else
LOCO* slot=lookupSpeedTable(cab);
if (!slot) return 0; // use default frequency
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)(slot->functions >>29);
//DIAG(F("Speed table %d functions %l shifted %d"), reg, slot->functions, res);
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
}
@ -215,7 +172,9 @@ uint8_t DCC::getThrottleFrequency(int cab) {
// returns direction on loco
// or true/forward on "loco not found"
bool DCC::getThrottleDirection(int cab) {
return getThrottleSpeedByte(cab) & 0x80;
int reg=lookupSpeedTable(cab);
if (reg<0) return true;
return (speedTable[reg].speedCode & 0x80) !=0;
}
// Set function to value on or off
@ -239,7 +198,7 @@ bool DCC::setFn( int cab, int16_t functionNumber, bool on) {
b[nB++] = (functionNumber & 0x7F) | (on ? 0x80 : 0); // low order bits and state flag
b[nB++] = functionNumber >>7 ; // high order bits
}
DCCQueue::scheduleDCCPacket(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
@ -248,21 +207,22 @@ bool DCC::setFn( int cab, int16_t functionNumber, bool on) {
if (functionNumber > 31)
return true;
LOCO * slot = lookupSpeedTable(cab);
int reg = lookupSpeedTable(cab);
if (reg<0) return false;
// Take care of functions:
// Set state of function
uint32_t previous=slot->functions;
uint32_t previous=speedTable[reg].functions;
uint32_t funcmask = (1UL<<functionNumber);
if (on) {
slot->functions |= funcmask;
speedTable[reg].functions |= funcmask;
} else {
slot->functions &= ~funcmask;
speedTable[reg].functions &= ~funcmask;
}
if (slot->functions != previous) {
if (speedTable[reg].functions != previous) {
if (functionNumber <= 28)
updateGroupflags(slot->groupFlags, functionNumber);
CommandDistributor::broadcastLoco(slot);
updateGroupflags(speedTable[reg].groupFlags, functionNumber);
CommandDistributor::broadcastLoco(reg);
}
return true;
}
@ -279,10 +239,12 @@ void DCC::changeFn( int cab, int16_t functionNumber) {
int8_t DCC::getFn( int cab, int16_t functionNumber) {
if (cab<=0 || functionNumber>31)
return -1; // unknown
auto slot = lookupSpeedTable(cab);
int reg = lookupSpeedTable(cab);
if (reg<0)
return -1;
unsigned long funcmask = (1UL<<functionNumber);
return (slot->functions & funcmask)? 1 : 0;
return (speedTable[reg].functions & funcmask)? 1 : 0;
}
// Set the group flag to say we have touched the particular group.
@ -299,22 +261,22 @@ void DCC::updateGroupflags(byte & flags, int16_t functionNumber) {
uint32_t DCC::getFunctionMap(int cab) {
if (cab<=0) return 0; // unknown pretend all functions off
auto slot = lookupSpeedTable(cab,false);
return slot?slot->functions:0;
int reg = lookupSpeedTable(cab);
return (reg<0)?0:speedTable[reg].functions;
}
// saves DC frequency (0..3) in spare functions 29,30,31
void DCC::setDCFreq(int cab,byte freq) {
if (cab==0 || freq>3) return;
auto slot=lookupSpeedTable(cab,true);
auto reg=lookupSpeedTable(cab,true);
// drop and replace F29,30,31 (top 3 bits)
auto newFunctions=slot->functions & 0x1FFFFFFFUL;
auto newFunctions=speedTable[reg].functions & 0x1FFFFFFFUL;
if (freq==1) newFunctions |= (1UL<<29); // F29
else if (freq==2) newFunctions |= (1UL<<30); // F30
else if (freq==3) newFunctions |= (1UL<<31); // F31
if (newFunctions==slot->functions) return; // no change
slot->functions=newFunctions;
CommandDistributor::broadcastLoco(slot);
if (newFunctions==speedTable[reg].functions) return; // no change
speedTable[reg].functions=newFunctions;
CommandDistributor::broadcastLoco(reg);
}
void DCC::setAccessory(int address, byte port, bool gate, byte onoff /*= 2*/) {
@ -340,17 +302,16 @@ void DCC::setAccessory(int address, byte port, bool gate, byte onoff /*= 2*/) {
// second byte is of the form 1AAACPPG, where C is 1 for on, PP the ports 0 to 3 and G the gate (coil).
b[0] = address % 64 + 128;
b[1] = ((((address / 64) % 8) << 4) + (port % 4 << 1) + gate % 2) ^ 0xF8;
if (onoff==0) { // off packet only
b[1] &= ~0x08; // set C to 0
DCCQueue::scheduleDCCPacket(b, 2, 3);
} else if (onoff==1) { // on packet only
DCCQueue::scheduleDCCPacket(b, 2, 3);
} else { // auto timed on then off
DCCQueue::scheduleAccOnOffPacket(b, 2, 3, 100); // On then off after 100mS
}
if (onoff != 0) {
DCCWaveform::mainTrack.schedulePacket(b, 2, 3); // Repeat on packet three times
#if defined(EXRAIL_ACTIVE)
if (onoff !=0) RMFT2::activateEvent(address<<2|port,gate);
RMFT2::activateEvent(address<<2|port,gate);
#endif
}
if (onoff != 1) {
b[1] &= ~0x08; // set C to 0
DCCWaveform::mainTrack.schedulePacket(b, 2, 3); // Repeat off packet three times
}
}
bool DCC::setExtendedAccessory(int16_t address, int16_t value, byte repeats) {
@ -400,7 +361,7 @@ whole range of the 11 bits sent to track.
| (((~(address>>8)) & 0x07)<<4) // shift out 8, invert, mask 3 bits, shift up 4
| ((address & 0x03)<<1); // mask 2 bits, shift up 1
b[2]=value;
DCCQueue::scheduleDCCPacket(b, sizeof(b), repeats);
DCCWaveform::mainTrack.schedulePacket(b, sizeof(b), repeats);
return true;
}
@ -419,26 +380,7 @@ void DCC::writeCVByteMain(int cab, int cv, byte bValue) {
b[nB++] = cv2(cv);
b[nB++] = bValue;
DCCQueue::scheduleDCCPacket(b, nB, 4);
}
//
// readCVByteMain: Read a byte with PoM on main.
// This requires Railcom active
//
void DCC::readCVByteMain(int cab, int cv, ACK_CALLBACK callback) {
byte b[5];
byte nB = 0;
if (cab > HIGHEST_SHORT_ADDR)
b[nB++] = highByte(cab) | 0xC0; // convert train number into a two-byte address
b[nB++] = lowByte(cab);
b[nB++] = cv1(READ_BYTE_MAIN, cv); // any CV>1023 will become modulus(1024) due to bit-mask of 0x03
b[nB++] = cv2(cv);
b[nB++] = 0;
DCCQueue::scheduleDCCPacket(b, nB, 4);
Railcom::anticipate(cab,cv,callback);
DCCWaveform::mainTrack.schedulePacket(b, nB, 4);
}
//
@ -459,45 +401,7 @@ void DCC::writeCVBitMain(int cab, int cv, byte bNum, bool bValue) {
b[nB++] = cv2(cv);
b[nB++] = WRITE_BIT | (bValue ? BIT_ON : BIT_OFF) | bNum;
DCCQueue::scheduleDCCPacket(b, nB, 4);
}
bool DCC::setTime(uint16_t minutes,uint8_t speed, bool suddenChange) {
/* see rcn-122
5 Global commands
These commands are sent and begin exclusively with a broadcast address 0
always with {synchronous bits} 0 0000-0000 and end with the checksum
... PPPPPPPP 1. Therefore, only the bytes of the commands and not that of
shown below whole package shown. The commands can be used by vehicle and
accessory decoders alike.
5.1 Time command
This command is four bytes long and has the format:
1100-0001 CCxx-xxxx xxxx-xxxxx xxxx-xxxx
CC indicates what data is transmitted in the packet:
CC = 00 Model Time
1100-0001 00MM-MMMM WWWH-HHHH U0BB-BBBB with:
MMMMMM = Minutes, Value range: 0..59
WWW = Day of the Week, Value range: 0 = Monday, 1 = Tuesday, 2 = Wednesday,
3 = Thursday, 4 = Friday, 5 = Saturday, 6 = Sunday, 7 = Weekday
is not supported.
HHHHH = Hours, value range: 0..23
U =
Update, i.e. the time has changed suddenly, e.g. by a new one timetable to start.
Up to 4 can occur per sudden change commands can be marked like this.
BBBBBB = Acceleration factor, value range 0..63. An acceleration factor of 0 means the
model clock has been stopped, a factor of 1 corresponds to real time, at 2 the
clock runs twice as fast, at three times as fast as real time, etc.
*/
if (minutes>=1440 || speed>63 ) return false;
byte b[5];
b[0]=0; // broadcast address
b[1]=0b11000001; // 1100-0001 (model time)
b[2]=minutes % 60 ; // MM
b[3]= 0b11100000 | (minutes/60); // 111H-HHHH weekday not supported
b[4]= (suddenChange ? 0b10000000 : 0) | speed;
DCCQueue::scheduleDCCPacket(b, sizeof(b), 2);
return true;
DCCWaveform::mainTrack.schedulePacket(b, nB, 4);
}
FSH* DCC::getMotorShieldName() {
@ -828,9 +732,10 @@ void DCC::setConsistId(int id,bool reverse,ACK_CALLBACK callback) {
void DCC::forgetLoco(int cab) { // removes any speed reminders for this loco
setThrottle2(cab,1); // ESTOP this loco if still on track
auto slot=lookupSpeedTable(cab, false);
if (slot) {
slot->loco=-1; // no longer used but not end of world
int reg=lookupSpeedTable(cab, false);
if (reg>=0) {
speedTable[reg].loco=0;
setThrottle2(cab,1); // ESTOP if this loco still on track
CommandDistributor::broadcastForgetLoco(cab);
}
}
@ -838,7 +743,7 @@ void DCC::forgetAllLocos() { // removes all speed reminders
setThrottle2(0,1); // ESTOP all locos still on track
for (int i=0;i<MAX_LOCOS;i++) {
if (speedTable[i].loco) CommandDistributor::broadcastForgetLoco(speedTable[i].loco);
speedTable[i].loco=0; // no longer used and looks like end
speedTable[i].loco=0;
}
}
@ -846,79 +751,33 @@ byte DCC::loopStatus=0;
void DCC::loop() {
TrackManager::loop(); // power overload checks
if (DCCWaveform::mainTrack.isReminderWindowOpen()) {
// Now is a good time to choose a packet to be sent
// Either highest priority from the queues or a reminder
if (!DCCQueue::scheduleNext()) {
issueReminders();
DCCQueue::scheduleNext(); // push through any just created reminder
}
}
issueReminders();
}
void DCC::issueReminders() {
// if the main track transmitter still has a pending packet, skip this time around.
if (!DCCWaveform::mainTrack.isReminderWindowOpen()) return;
// Move to next loco slot. If occupied, send a reminder.
auto slot = nextLocoReminder;
if (slot >= &speedTable[MAX_LOCOS]) slot=&speedTable[0]; // Go to start of table
if (slot->loco > 0)
if (!issueReminder(slot))
return;
// a loco=0 is at the end of the list, a loco <0 is deleted
if (slot->loco==0) nextLocoReminder = &speedTable[0];
else nextLocoReminder=slot+1;
int reg = lastLocoReminder+1;
if (reg > highestUsedReg) reg = 0; // Go to start of table
if (speedTable[reg].loco > 0) {
// have found loco to remind
if (issueReminder(reg))
lastLocoReminder = reg;
} else
lastLocoReminder = reg;
}
int16_t normalize(byte speed) {
if (speed & 0x80) return speed & 0x7F;
return 0-1-speed;
}
byte dccalize(int16_t speed) {
if (speed>127) return 0xFF; // 127 forward
if (speed<-127) return 0x7F; // 127 reverse
if (speed >=0) return speed | 0x80;
// negative speeds... -1==dcc 0, -2==dcc 1
return (int16_t)-1 - speed;
}
bool DCC::issueReminder(LOCO * slot) {
unsigned long functions=slot->functions;
int loco=slot->loco;
byte flags=slot->groupFlags;
bool DCC::issueReminder(int reg) {
unsigned long functions=speedTable[reg].functions;
int loco=speedTable[reg].loco;
byte flags=speedTable[reg].groupFlags;
switch (loopStatus) {
case 0: {
// calculate any momentum change going on
auto sc=slot->speedCode;
if (slot->targetSpeed!=sc) {
// calculate new speed code
auto now=millis();
int16_t delay=now-slot->momentum_base;
auto millisPerNotch=MOMENTUM_FACTOR * (int16_t)getMomentum(slot);
// allow for momentum change to 0 while accelerating/slowing
auto ticks=(millisPerNotch>0)?(delay/millisPerNotch):500;
if (ticks>0) {
auto current=normalize(sc); // -128..+127
auto target=normalize(slot->targetSpeed);
// DIAG(F("Momentum l=%d ti=%d sc=%d c=%d t=%d"),loco,ticks,sc,current,target);
if (current<target) { // accelerate
current+=ticks;
if (current>target) current=target;
}
else { // slow
current-=ticks;
if (current<target) current=target;
}
sc=dccalize(current);
//DIAG(F("c=%d newsc=%d"),current,sc);
slot->speedCode=sc;
TrackManager::setDCSignal(loco,sc); // in case this is a dcc track on this addr
slot->momentum_base=now;
}
}
// DIAG(F("Reminder %d speed %d"),loco,slot->speedCode);
setThrottle2(loco, sc);
}
break;
case 0:
// DIAG(F("Reminder %d speed %d"),loco,speedTable[reg].speedCode);
setThrottle2(loco, speedTable[reg].speedCode);
break;
case 1: // remind function group 1 (F0-F4)
if (flags & FN_GROUP_1)
#ifndef DISABLE_FUNCTION_REMINDERS
@ -979,128 +838,70 @@ byte DCC::cv2(int cv) {
return lowByte(cv);
}
DCC::LOCO * DCC::lookupSpeedTable(int locoId, bool autoCreate) {
int DCC::lookupSpeedTable(int locoId, bool autoCreate) {
// determine speed reg for this loco
LOCO * firstEmpty=nullptr;
SLOTLOOP {
if (firstEmpty==nullptr && slot->loco<=0) firstEmpty=slot;
if (slot->loco == locoId) return slot;
if (slot->loco==0) break;
int firstEmpty = MAX_LOCOS;
int reg;
for (reg = 0; reg < MAX_LOCOS; reg++) {
if (speedTable[reg].loco == locoId) break;
if (speedTable[reg].loco == 0 && firstEmpty == MAX_LOCOS) firstEmpty = reg;
}
if (!autoCreate) return nullptr;
if (firstEmpty==nullptr) {
// return last slot if full
DIAG(F("Too many locos, reusing last slot"));
firstEmpty=&speedTable[MAX_LOCOS-1];
// return -1 if not found and not auto creating
if (reg== MAX_LOCOS && !autoCreate) return -1;
if (reg == MAX_LOCOS) reg = firstEmpty;
if (reg >= MAX_LOCOS) {
DIAG(F("Too many locos"));
return -1;
}
// fill first empty slot with new entry
firstEmpty->loco = locoId;
firstEmpty->speedCode=128; // default direction forward
firstEmpty->targetSpeed=128; // default direction forward
firstEmpty->groupFlags=0;
firstEmpty->functions=0;
firstEmpty->momentumA=MOMENTUM_USE_DEFAULT;
firstEmpty->momentumD=MOMENTUM_USE_DEFAULT;
return firstEmpty;
if (reg==firstEmpty){
speedTable[reg].loco = locoId;
speedTable[reg].speedCode=128; // default direction forward
speedTable[reg].groupFlags=0;
speedTable[reg].functions=0;
}
if (reg > highestUsedReg) highestUsedReg = reg;
return reg;
}
bool DCC::setMomentum(int locoId,int16_t accelerating, int16_t decelerating) {
if (locoId<0) return false;
if (locoId==0) {
if (accelerating<0 || decelerating<0) return false;
defaultMomentumA=accelerating/MOMENTUM_FACTOR;
defaultMomentumD=decelerating/MOMENTUM_FACTOR;
return true;
void DCC::updateLocoReminder(int loco, byte speedCode) {
if (loco==0) {
// broadcast stop/estop but dont change direction
for (int reg = 0; reg <= highestUsedReg; reg++) {
if (speedTable[reg].loco==0) continue;
byte newspeed=(speedTable[reg].speedCode & 0x80) | (speedCode & 0x7f);
if (speedTable[reg].speedCode != newspeed) {
speedTable[reg].speedCode = newspeed;
CommandDistributor::broadcastLoco(reg);
}
}
return;
}
// -1 is ok and means this loco should use the default.
if (accelerating<-1 || decelerating<-1) return false;
if (accelerating/MOMENTUM_FACTOR >= MOMENTUM_USE_DEFAULT ||
decelerating/MOMENTUM_FACTOR >= MOMENTUM_USE_DEFAULT) return false;
// Values stored are 255=MOMENTUM_USE_DEFAULT, or millis/MOMENTUM_FACTOR.
// This is to keep the values in a byte rather than int16
// thus saving 2 bytes RAM per loco slot.
LOCO* slot=lookupSpeedTable(locoId,true);
slot->momentumA=(accelerating<0)? MOMENTUM_USE_DEFAULT: (accelerating/MOMENTUM_FACTOR);
slot->momentumD=(decelerating<0)? MOMENTUM_USE_DEFAULT: (decelerating/MOMENTUM_FACTOR);
return true;
}
void DCC::estopAll() {
setThrottle2(0,1); // estop all locos
TrackManager::setDCSignal(0,1);
// remind stop/estop but dont change direction
SLOTLOOP {
if (slot->loco<=0) continue;
byte newspeed=(slot->targetSpeed & 0x80) | 0x01;
slot->speedCode = newspeed;
slot->targetSpeed = newspeed;
CommandDistributor::broadcastLoco(slot);
// determine speed reg for this loco
int reg=lookupSpeedTable(loco);
if (reg>=0 && speedTable[reg].speedCode!=speedCode) {
speedTable[reg].speedCode = speedCode;
CommandDistributor::broadcastLoco(reg);
}
}
DCC::LOCO DCC::speedTable[MAX_LOCOS];
DCC::LOCO * DCC::nextLocoReminder = &DCC::speedTable[0];
int DCC::lastLocoReminder = 0;
int DCC::highestUsedReg = 0;
void DCC::displayCabList(Print * stream) {
StringFormatter::send(stream,F("<*\n"));
int used=0;
SLOTLOOP {
if (slot->loco==0) break; // no more locos
if (slot->loco>0) {
for (int reg = 0; reg <= highestUsedReg; reg++) {
if (speedTable[reg].loco>0) {
used ++;
StringFormatter::send(stream,F("cab=%d, speed=%d, target=%d, momentum=%d/%d, block=%d\n"),
slot->loco, slot->speedCode, slot->targetSpeed,
slot->momentumA, slot->momentumD, slot->blockOccupied);
StringFormatter::send(stream,F("cab=%d, speed=%d, dir=%c \n"),
speedTable[reg].loco, speedTable[reg].speedCode & 0x7f,(speedTable[reg].speedCode & 0x80) ? 'F':'R');
}
}
StringFormatter::send(stream,F("Used=%d, max=%d, momentum=%d/%d *>\n"),
used,MAX_LOCOS, DCC::defaultMomentumA,DCC::defaultMomentumD);
}
void DCC::setLocoInBlock(int loco, uint16_t blockid, bool exclusive) {
// update block loco is in, tell exrail leaving old block, and entering new.
// NOTE: The loco table scanning is really inefficient and needs rewriting
// This was done once in the momentum poc.
#ifdef EXRAIL_ACTIVE
auto slot=lookupSpeedTable(loco,true);
if (!slot) return;
auto oldBlock=slot->blockOccupied;
if (oldBlock==blockid) return;
if (oldBlock) RMFT2::blockEvent(oldBlock,loco,false);
slot->blockOccupied=blockid;
if (blockid) RMFT2::blockEvent(blockid,loco,true);
if (exclusive) {
SLOTLOOP {
if (slot->loco==0) break; // no more locos
if (slot->loco>0) {
if (slot->loco!=loco && slot->blockOccupied==blockid) {
RMFT2::blockEvent(blockid,slot->loco,false);
slot->blockOccupied=0;
}
}
}
}
#endif
}
void DCC::clearBlock(uint16_t blockid) {
// Railcom reports block empty... tell Exrail about all leavers
#ifdef EXRAIL_ACTIVE
SLOTLOOP {
if (slot->loco==0) break; // no more locos
if (slot->loco>0) {
if (slot->blockOccupied==blockid) {
RMFT2::blockEvent(blockid,slot->loco,false);
slot->blockOccupied=0;
}
}
}
#endif
StringFormatter::send(stream,F("Used=%d, max=%d\n"),used,MAX_LOCOS);
}

32
DCC.h
View File

@ -3,7 +3,7 @@
* © 2021 Fred Decker
* © 2021 Herb Morton
* © 2020-2021 Harald Barth
* © 2020-2025 Chris Harlow
* © 2020-2021 Chris Harlow
* All rights reserved.
*
* This file is part of Asbelos DCC API
@ -59,15 +59,11 @@ public:
// Public DCC API functions
static void setThrottle(uint16_t cab, uint8_t tSpeed, bool tDirection);
static void estopAll();
static int8_t getThrottleSpeed(int cab);
static uint8_t getThrottleSpeedByte(int cab);
static uint8_t getLocoSpeedByte(int cab); // may lag throttle
static uint8_t getThrottleFrequency(int cab);
static bool getThrottleDirection(int cab);
static void writeCVByteMain(int cab, int cv, byte bValue);
static void readCVByteMain(int cab, int cv, ACK_CALLBACK callback);
static void writeCVBitMain(int cab, int cv, byte bNum, bool bValue);
static void setFunction(int cab, byte fByte, byte eByte);
static bool setFn(int cab, int16_t functionNumber, bool on);
@ -87,9 +83,7 @@ public:
static void writeCVBit(int16_t cv, byte bitNum, bool bitValue, ACK_CALLBACK callback);
static void verifyCVByte(int16_t cv, byte byteValue, ACK_CALLBACK callback);
static void verifyCVBit(int16_t cv, byte bitNum, bool bitValue, ACK_CALLBACK callback);
static bool setTime(uint16_t minutes,uint8_t speed, bool suddenChange);
static void setLocoInBlock(int loco, uint16_t blockid, bool exclusive);
static void clearBlock(uint16_t blockid);
static void getLocoId(ACK_CALLBACK callback);
static void setLocoId(int id,ACK_CALLBACK callback);
static void setConsistId(int id,bool reverse,ACK_CALLBACK callback);
@ -108,31 +102,20 @@ public:
byte speedCode;
byte groupFlags;
uint32_t functions;
// Momentum management variables
uint32_t momentum_base; // millis() when speed modified under momentum
byte momentumA, momentumD;
byte targetSpeed; // speed set by throttle
uint16_t blockOccupied; // railcom detected block
};
static const int16_t MOMENTUM_FACTOR=7;
static const byte MOMENTUM_USE_DEFAULT=255;
static bool linearAcceleration;
static byte getMomentum(LOCO * slot);
static LOCO speedTable[MAX_LOCOS];
static LOCO * lookupSpeedTable(int locoId, bool autoCreate=true);
static int lookupSpeedTable(int locoId, bool autoCreate=true);
static byte cv1(byte opcode, int cv);
static byte cv2(int cv);
static bool setMomentum(int locoId,int16_t accelerating, int16_t decelerating);
private:
static byte loopStatus;
static byte defaultMomentumA; // Accelerating
static byte defaultMomentumD; // Accelerating
static void setThrottle2(uint16_t cab, uint8_t speedCode);
static void updateLocoReminder(int loco, byte speedCode);
static void setFunctionInternal(int cab, byte fByte, byte eByte, byte count);
static bool issueReminder(LOCO * slot);
static LOCO* nextLocoReminder;
static bool issueReminder(int reg);
static int lastLocoReminder;
static int highestUsedReg;
static FSH *shieldName;
static byte globalSpeedsteps;
@ -143,7 +126,6 @@ private:
// NMRA codes #
static const byte SET_SPEED = 0x3f;
static const byte WRITE_BYTE_MAIN = 0xEC;
static const byte READ_BYTE_MAIN = 0xE4;
static const byte WRITE_BIT_MAIN = 0xE8;
static const byte WRITE_BYTE = 0x7C;
static const byte VERIFY_BYTE = 0x74;

View File

@ -6,7 +6,7 @@
* © 2020-2023 Harald Barth
* © 2020-2021 M Steve Todd
* © 2020-2021 Fred Decker
* © 2020-2025 Chris Harlow
* © 2020-2021 Chris Harlow
* © 2022 Colin Murdoch
* All rights reserved.
*
@ -64,12 +64,11 @@ Once a new OPCODE is decided upon, update this list.
I, Turntable object command, control, and broadcast
j, Throttle responses
J, Throttle queries
k, Block exit (Railcom)
K, Block enter (Railcom)
k, Reserved for future use - Potentially Railcom
K, Reserved for future use - Potentially Railcom
l, Loco speedbyte/function map broadcast
L, Reserved for LCC interface (implemented in EXRAIL)
m, message to throttles (broadcast output)
m, set momentum
m, message to throttles broadcast
M, Write DCC packet
n, Reserved for SensorCam
N, Reserved for Sensorcam
@ -168,8 +167,10 @@ int16_t DCCEXParser::splitValues(int16_t result[MAX_COMMAND_PARAMS], byte *cmd,
break;
if (hot == '\0')
return -1;
if (hot == '>')
if (hot == '>') {
*remainingCmd = '\0'; // terminate the cmd string with 0 instead of '>'
return parameterCount;
}
state = 2;
continue;
@ -238,7 +239,6 @@ int16_t DCCEXParser::splitValues(int16_t result[MAX_COMMAND_PARAMS], byte *cmd,
extern __attribute__((weak)) void myFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]);
FILTER_CALLBACK DCCEXParser::filterCallback = myFilter;
FILTER_CALLBACK DCCEXParser::filterRMFTCallback = 0;
FILTER_CALLBACK DCCEXParser::filterCamParserCallback = 0;
AT_COMMAND_CALLBACK DCCEXParser::atCommandCallback = 0;
// deprecated
@ -250,10 +250,6 @@ void DCCEXParser::setRMFTFilter(FILTER_CALLBACK filter)
{
filterRMFTCallback = filter;
}
void DCCEXParser::setCamParserFilter(FILTER_CALLBACK filter)
{
filterCamParserCallback = filter;
}
void DCCEXParser::setAtCommandCallback(AT_COMMAND_CALLBACK callback)
{
atCommandCallback = callback;
@ -271,17 +267,22 @@ void DCCEXParser::parse(const FSH * cmd) {
// See documentation on DCC class for info on this section
void DCCEXParser::parse(Print *stream, byte *com, RingStream *ringStream) {
// This function can get stings of the form "<C OMM AND>" or "C OMM AND"
// found is true first after the leading "<" has been passed
// This function can get stings of the form "<C OMM AND>" or "C OMM AND>"
// found is true first after the leading "<" has been passed which results
// in parseOne() getting c="C OMM AND>"
byte *cForLater = NULL;
bool found = (com[0] != '<');
for (byte *c=com; c[0] != '\0'; c++) {
if (found) {
parseOne(stream, c, ringStream);
cForLater = c;
found=false;
}
if (c[0] == '<')
if (c[0] == '<') {
if (cForLater) parseOne(stream, cForLater, ringStream);
found = true;
}
}
if (cForLater) parseOne(stream, cForLater, ringStream);
}
void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
@ -309,8 +310,6 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
filterCallback(stream, opcode, params, p);
if (filterRMFTCallback && opcode!='\0')
filterRMFTCallback(stream, opcode, params, p);
if (filterCamParserCallback && opcode!='\0')
filterCamParserCallback(stream, opcode, params, p);
// Functions return from this switch if complete, break from switch implies error <X> to send
switch (opcode)
@ -324,9 +323,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
int16_t direction;
if (params==1) { // <t cab> display state
if (p[0]<=0) break;
CommandDistributor::broadcastLoco(DCC::lookupSpeedTable(p[0],false));
return;
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)
@ -488,35 +490,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
DCC::writeCVByteMain(p[0], p[1], p[2]);
return;
#ifdef HAS_ENOUGH_MEMORY
case 'r': // READ CV on MAIN <r CAB CV> Requires Railcom
if (params != 2)
break;
if (!DCCWaveform::isRailcom()) break;
if (!stashCallback(stream, p, ringStream)) break;
DCC::readCVByteMain(p[0], p[1],callback_r);
return;
#endif
case 'b': // WRITE CV BIT ON MAIN <b CAB CV BIT VALUE>
if (params != 4)
break;
DCC::writeCVBitMain(p[0], p[1], p[2], p[3]);
return;
#endif
case 'm': // <m cabid momentum [braking]>
// <m LINEAR|POWER>
if (params==1) {
if (p[0]=="LINEAR"_hk) DCC::linearAcceleration=true;
else if (p[0]=="POWER"_hk) DCC::linearAcceleration=false;
else break;
return;
}
if (params<2 || params>3) break;
if (params==2) p[2]=p[1];
if (DCC::setMomentum(p[0],p[1],p[2])) return;
break;
case 'M': // WRITE TRANSPARENT DCC PACKET MAIN <M REG X1 ... X9>
#ifndef DISABLE_PROG
@ -666,7 +645,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
}
case '!': // ESTOP ALL <!>
DCC::estopAll(); // 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;
#ifdef HAS_ENOUGH_MEMORY
@ -905,11 +884,15 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
if (parseI(stream, params, p))
return;
break;
#endif
#ifndef IO_NO_HAL
case 'N': // <N commands for SensorCam
if (CamParser::parseN(stream,params,p)) return;
break;
#endif
case '/': // implemented in EXRAIL parser
case 'L': // LCC interface implemented in EXRAIL parser
case 'N': // interface implemented in CamParser
break; // Will <X> if not intercepted by filters
break; // Will <X> if not intercepted by EXRAIL
#ifndef DISABLE_VDPY
case '@': // JMRI saying "give me virtual LCD msgs"
@ -1236,10 +1219,6 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
return true;
#ifdef HAS_ENOUGH_MEMORY
case "RAILCOM"_hk: // <D RAILCOM ON/OFF>
Diag::RAILCOM = onOff;
return true;
case "WIFI"_hk: // <D WIFI ON/OFF>
Diag::WIFI = onOff;
return true;
@ -1255,10 +1234,6 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
case "LCN"_hk: // <D LCN ON/OFF>
Diag::LCN = onOff;
return true;
case "WEBSOCKET"_hk: // <D WEBSOCKET ON/OFF>
Diag::WEBSOCKET = onOff;
return true;
#endif
#ifndef DISABLE_EEPROM
case "EEPROM"_hk: // <D EEPROM NumEntries>
@ -1451,12 +1426,6 @@ void DCCEXParser::callback_R(int16_t result)
commitAsyncReplyStream();
}
void DCCEXParser::callback_r(int16_t result)
{
StringFormatter::send(getAsyncReplyStream(), F("<r %d %d %d >\n"), stashP[0], stashP[1], result);
commitAsyncReplyStream();
}
void DCCEXParser::callback_Rloco(int16_t result) {
const FSH * detail;
if (result<=0) {

View File

@ -1,7 +1,7 @@
/*
* © 2021 Mike S
* © 2021 Fred Decker
* © 2020-2025 Chris Harlow
* © 2020-2021 Chris Harlow
* All rights reserved.
*
* This file is part of Asbelos DCC API
@ -37,7 +37,6 @@ struct DCCEXParser
static void parseOne(Print * stream, byte * command, RingStream * ringStream);
static void setFilter(FILTER_CALLBACK filter);
static void setRMFTFilter(FILTER_CALLBACK filter);
static void setCamParserFilter(FILTER_CALLBACK filter);
static void setAtCommandCallback(AT_COMMAND_CALLBACK filter);
static const int MAX_COMMAND_PARAMS=10; // Must not exceed this
@ -69,8 +68,7 @@ struct DCCEXParser
static void callback_W(int16_t result);
static void callback_W4(int16_t result);
static void callback_B(int16_t result);
static void callback_R(int16_t result); // prog
static void callback_r(int16_t result); // main
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);
@ -78,7 +76,6 @@ struct DCCEXParser
static void callback_Vbyte(int16_t result);
static FILTER_CALLBACK filterCallback;
static FILTER_CALLBACK filterRMFTCallback;
static FILTER_CALLBACK filterCamParserCallback;
static AT_COMMAND_CALLBACK atCommandCallback;
static bool funcmap(int16_t cab, byte value, byte fstart, byte fstop);
static void sendFlashList(Print * stream,const int16_t flashList[]);

View File

@ -1,185 +0,0 @@
/*
* © 2025 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/>.
*/
#include "Arduino.h"
#include "defines.h"
#include "DCCQueue.h"
#include "DCCWaveform.h"
#include "DIAG.h"
// create statics
DCCQueue* DCCQueue::lowPriorityQueue=new DCCQueue();
DCCQueue* DCCQueue::highPriorityQueue=new DCCQueue();
PendingSlot* DCCQueue::recycleList=nullptr;
DCCQueue::DCCQueue() {
head=nullptr;
tail=nullptr;
}
void DCCQueue::addQueue(PendingSlot* p) {
if (tail) tail->next=p;
else head=p;
tail=p;
p->next=nullptr;
}
void DCCQueue::jumpQueue(PendingSlot* p) {
p->next=head;
head=p;
if (!tail) tail=p;
}
void DCCQueue::recycle(PendingSlot* p) {
p->next=recycleList;
recycleList=p;
}
// Packet joins end of low priority queue.
void DCCQueue::scheduleDCCPacket(byte* packet, byte length, byte repeats) {
lowPriorityQueue->addQueue(getSlot(NORMAL_PACKET,packet,length,repeats,0));
}
// Packet replaces existing loco speed packet or joins end of high priority queue.
void DCCQueue::scheduleDCCSpeedPacket(byte* packet, byte length, byte repeats, uint16_t loco) {
for (auto p=highPriorityQueue->head;p;p=p->next) {
if (p->locoId==loco) {
// replace existing packet
memcpy(p->packet,packet,length);
p->packetLength=length;
p->packetRepeat=repeats;
return;
}
}
highPriorityQueue->addQueue(getSlot(NORMAL_PACKET,packet,length,repeats,loco));
}
// ESTOP -
// any outstanding throttle packet for this loco (all if loco=0) discarded
// Packet joins start of queue,
void DCCQueue::scheduleEstopPacket(byte* packet, byte length, byte repeats,uint16_t loco) {
// DIAG(F("DCC ESTOP loco=%d"),loco);
// kill any existing throttle packets for this loco
PendingSlot * previous=nullptr;
auto p=highPriorityQueue->head;
while(p) {
if (loco==0 || p->locoId==loco) {
// drop this packet from the highPriority queue
if (previous) previous->next=p->next;
else highPriorityQueue->head=p->next;
recycle(p); // recycle this slot
// address next packet
p=previous?previous->next : highPriorityQueue->head;
}
else {
previous=p;
p=p->next;
}
}
// add the estop packet to the start of the queue
highPriorityQueue->jumpQueue(getSlot(NORMAL_PACKET,packet,length,repeats,0));
}
// Accessory gate-On Packet joins end of queue as normal.
// When dequeued, packet is retained at start of queue
// but modified to gate-off and given the delayed start.
// getNext will ignore this packet until the requested start time.
void DCCQueue::scheduleAccOnOffPacket(byte* packet, byte length, byte repeats,int16_t delayms) {
auto p=getSlot(ACC_ON_PACKET,packet,length,repeats,0);
p->delayOff=delayms;
lowPriorityQueue->addQueue(p);
};
// Obtain packet (fills packet, length and repeats)
// returns 0 length if nothing in queue.
bool DCCQueue::scheduleNext() {
// check high priority queue first
if (!DCCWaveform::mainTrack.isReminderWindowOpen()) return false;
PendingSlot* previous=nullptr;
for (auto p=highPriorityQueue->head;p;p=p->next) {
// skip over pending ACC_OFF packets which are still delayed
if (p->type == ACC_OFF_PACKET && millis()<p->startTime) continue;
// use this slot
DCCWaveform::mainTrack.schedulePacket(p->packet,p->packetLength,p->packetRepeat);
// remove this slot from the queue
if (previous) previous->next=p->next;
else highPriorityQueue->head=p->next;
if (!highPriorityQueue->head) highPriorityQueue->tail=nullptr;
// and recycle it.
recycle(p);
return true;
}
// No high priopity packets found, check low priority queue
auto p=lowPriorityQueue->head;
if (!p) return false; // nothing in queues
// schedule first packet in queue
DCCWaveform::mainTrack.schedulePacket(p->packet,p->packetLength,p->packetRepeat);
// remove from queue
lowPriorityQueue->head=p->next;
if (!lowPriorityQueue->head) lowPriorityQueue->tail=nullptr;
if (p->type == ACC_ON_PACKET) {
// convert to a delayed off packet and jump the high priority queue
p->type= ACC_OFF_PACKET;
p->packet[1] &= ~0x08; // set C to 0 (gate off)
p->startTime=millis()+p->delayOff;
highPriorityQueue->jumpQueue(p);
}
else recycle(p); // recycle this slot
return true;
}
// obtain and initialise slot for a PendingSlot.
PendingSlot* DCCQueue::getSlot(PendingType type, byte* packet, byte length, byte repeats,uint16_t loco) {
PendingSlot * p;
if (recycleList) {
p=recycleList;
recycleList=p->next;
}
else {
DIAG(F("New DCC queue slot"));
p=new PendingSlot; // need a queue entry
}
p->next=nullptr;
p->type=type;
p->packetLength=length;
p->packetRepeat=repeats;
memcpy((void*)p->packet,packet,length);
p->locoId=loco;
return p;
}

View File

@ -1,84 +0,0 @@
/*
* © 2025 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 DCCQueue_h
#define DCCQueue_h
#include "Arduino.h"
#include "DCCWaveform.h"
enum PendingType:byte {NORMAL_PACKET,ACC_ON_PACKET,ACC_OFF_PACKET,DEAD_PACKET};
struct PendingSlot {
PendingSlot* next;
PendingType type;
byte packetLength;
byte packetRepeat;
byte packet[MAX_PACKET_SIZE];
union { // use depends on packet type
uint16_t locoId; // NORMAL_PACKET .. only set >0 for speed change packets
// so they can be easily discarded if an estop jumps the queue.
uint16_t delayOff; // ACC_ON_PACKET delay to apply between on/off
uint32_t startTime; // ACC_OFF_PACKET time (mS) to transmit
};
};
class DCCQueue {
public:
// Non-speed packets are queued in the main queue
static void scheduleDCCPacket(byte* packet, byte length, byte repeats);
// Speed packets are queued in the high priority queue
static void scheduleDCCSpeedPacket(byte* packet, byte length, byte repeats, uint16_t loco);
// ESTOP packets jump the high priority queue and discard any outstanding throttle packets for this loco
static void scheduleEstopPacket(byte* packet, byte length, byte repeats,uint16_t loco);
// Accessory gate-On Packet joins end of main queue as normal.
// When dequeued, packet is modified to gate-off and given the delayed start in the high priority queue.
// getNext will ignore this packet until the requested start time.
static void scheduleAccOnOffPacket(byte* packet, byte length, byte repeats,int16_t delayms);
// Schedules a main track packet from the queues if none pending.
// returns true if a packet was scheduled.
static bool scheduleNext();
private:
// statics to manage high and low priority queues and recycleing of PENDINGs
static PendingSlot* recycleList;
static DCCQueue* highPriorityQueue;
static DCCQueue* lowPriorityQueue;
DCCQueue();
PendingSlot* head;
PendingSlot * tail;
// obtain and initialise slot for a PendingSlot.
static PendingSlot* getSlot(PendingType type, byte* packet, byte length, byte repeats, uint16_t loco);
static void recycle(PendingSlot* p);
void addQueue(PendingSlot * p);
void jumpQueue(PendingSlot * p);
};
#endif

View File

@ -2,7 +2,7 @@
* © 2021 Mike S
* © 2021-2023 Harald Barth
* © 2021 Fred Decker
* © 2021-2025 Chris Harlow
* © 2021 Chris Harlow
* © 2021 David Cutting
* All rights reserved.
*
@ -57,59 +57,66 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
TCCR1B = _BV(WGM13) | _BV(CS10); // Mode 8, clock select 1
TIMSK1 = _BV(TOIE1); // Enable Software interrupt
interrupts();
//diagnostic pinMode(4,OUTPUT);
}
void DCCTimer::startRailcomTimer(byte brakePin) {
(void) brakePin; // Ignored... works on pin 9 only
// diagnostic digitalWrite(4,HIGH);
/* The Railcom timer is started in such a way that it
- First triggers 58+29 uS after the previous TIMER1 tick.
- First triggers 28uS after the last TIMER1 tick.
This provides an accurate offset (in High Accuracy mode)
for the start of the Railcom cutout.
- Sets the Railcom pin high at first tick and subsequent ticks
until its reset to setting pin 9 low at next tick.
- Sets the Railcom pin high at first tick,
because its been setup with 100% PWM duty cycle.
- Cycles at 436uS so the second tick is the
correct distance from the cutout.
- Waveform code is responsible for resetting
any time between the first and second tick.
- Waveform code is responsible for altering the PWM
duty cycle to 0% any time between the first and last tick.
(there will be 7 DCC timer1 ticks in which to do this.)
*/
(void) brakePin; // Ignored... works on pin 9 only
const int cutoutDuration = 430; // Desired interval in microseconds
const int cycle=cutoutDuration/2;
const byte RailcomFudge0=58+58+29;
// Set Timer2 to CTC mode with set on compare match
TCCR2A = (1 << WGM21) | (1 << COM2B0) | (1 << COM2B1);
// Prescaler of 32
TCCR2B = (1 << CS21) | (1 << CS20);
OCR2A = cycle-1; // Compare match value for 430 uS
// Set up Timer2 for CTC mode (Clear Timer on Compare Match)
TCCR2A = 0; // Clear Timer2 control register A
TCCR2B = 0; // Clear Timer2 control register B
TCNT2 = 0; // Initialize Timer2 counter value to 0
// Configure Phase and Frequency Correct PWM mode
TCCR2A = (1 << COM2B1); // enable pwm on pin 9
TCCR2A |= (1 << WGM20);
// Set Timer 2 prescaler to 32
TCCR2B = (1 << CS21) | (1 << CS20); // 32 prescaler
// Set the compare match value for desired interval
OCR2A = (F_CPU / 1000000) * cutoutDuration / 64 - 1;
// Calculate the compare match value for desired duty cycle
OCR2B = OCR2A+1; // set duty cycle to 100%= OCR2A)
// Enable Timer2 output on pin 9 (OC2B)
DDRB |= (1 << DDB1);
// TODO Fudge TCNT2 to sync with last tcnt1 tick + 28uS
// RailcomFudge2 is the expected time from idealised
// setup call (at previous DCC timer interrupt) to the cutout.
// This value should be reduced to reflect the Timer1 value
// measuring the time since the previous hardware interrupt
byte tcfudge=TCNT1/16;
TCNT2=cycle-RailcomFudge0/2+tcfudge/2;
// Previous TIMER1 Tick was at rising end-of-packet bit
// Cutout starts half way through first preamble
// that is 2.5 * 58uS later.
}
// TCNT1 ticks 8 times / microsecond
// auto microsendsToFirstRailcomTick=(58+58+29)-(TCNT1/8);
// set the railcom timer counter allowing for phase-correct
// CHris's NOTE:
// I dont kniow quite how this calculation works out but
// it does seems to get a good answer.
TCNT2=193 + (ICR1 - TCNT1)/8;
}
void DCCTimer::ackRailcomTimer() {
// Change Timer2 to CTC mode with RESET pin 9 on next compare match
TCCR2A = (1 << WGM21) | (1 << COM2B1);
// diagnostic digitalWrite(4,LOW);
OCR2B= 0x00; // brake pin pwm duty cycle 0 at next tick
}

View File

@ -78,11 +78,17 @@ int DCCTimer::freeMemory() {
////////////////////////////////////////////////////////////////////////
#ifdef ARDUINO_ARCH_ESP32
#if __has_include("esp_idf_version.h")
#include "esp_idf_version.h"
#if ESP_IDF_VERSION_MAJOR > 4
#endif
#if ESP_IDF_VERSION_MAJOR == 4
// all well correct IDF version
#else
#error "DCC-EX does not support compiling with IDF version 5.0 or later. Downgrade your ESP32 library to a version that contains IDF version 4. Arduino ESP32 library 3.0.0 is too new. Downgrade to one of 2.0.9 to 2.0.17"
#endif
// protect all the rest of the code from IDF version 5
#if ESP_IDF_VERSION_MAJOR == 4
#include "DIAG.h"
#include <driver/adc.h>
#include <soc/sens_reg.h>
@ -322,5 +328,5 @@ void ADCee::scan() {
void ADCee::begin() {
}
#endif //IDF v4
#endif //ESP32

View File

@ -24,13 +24,14 @@
#ifndef ARDUINO_ARCH_ESP32
// This code is replaced entirely on an ESP32
#include <Arduino.h>
#include "DCCWaveform.h"
#include "TrackManager.h"
#include "DCCTimer.h"
#include "DCCACK.h"
#include "DIAG.h"
bool DCCWaveform::cutoutNextTime=false;
DCCWaveform DCCWaveform::mainTrack(PREAMBLE_BITS_MAIN, true);
DCCWaveform DCCWaveform::progTrack(PREAMBLE_BITS_PROG, false);
@ -70,18 +71,9 @@ void DCCWaveform::loop() {
#pragma GCC push_options
#pragma GCC optimize ("-O3")
void DCCWaveform::interruptHandler() {
// call the timer edge sensitive actions for progtrack and maintrack
// member functions would be cleaner but have more overhead
#if defined(HAS_ENOUGH_MEMORY)
if (cutoutNextTime) {
cutoutNextTime=false;
railcomSampleWindow=false; // about to cutout, stop reading railcom data.
railcomCutoutCounter++;
DCCTimer::startRailcomTimer(9);
}
#endif
byte sigMain=signalTransform[mainTrack.state];
byte sigProg=TrackManager::progTrackSyncMain? sigMain : signalTransform[progTrack.state];
@ -123,24 +115,19 @@ DCCWaveform::DCCWaveform( byte preambleBits, bool isMain) {
bytes_sent = 0;
bits_sent = 0;
}
bool DCCWaveform::railcomPossible=false; // High accuracy only
volatile bool DCCWaveform::railcomActive=false; // switched on by user
volatile bool DCCWaveform::railcomDebug=false; // switched on by user
volatile bool DCCWaveform::railcomSampleWindow=false; // true during packet transmit
volatile byte DCCWaveform::railcomCutoutCounter=0; // cyclic cutout
volatile byte DCCWaveform::railcomLastAddressHigh=0;
volatile byte DCCWaveform::railcomLastAddressLow=0;
bool DCCWaveform::setRailcom(bool on, bool debug) {
if (on && railcomPossible) {
if (on) {
// TODO check possible
railcomActive=true;
railcomDebug=debug;
}
else {
railcomActive=false;
railcomDebug=false;
railcomSampleWindow=false;
}
return railcomActive;
}
@ -153,37 +140,14 @@ void DCCWaveform::interrupt2() {
// or WAVE_HIGH_0 for a 0 bit.
if (remainingPreambles > 0 ) {
state=WAVE_MID_1; // switch state to trigger LOW on next interrupt
remainingPreambles--;
// As we get to the end of the preambles, open the reminder window.
// This delays any reminder insertion until the last moment so
// that the reminder doesn't block a more urgent packet.
reminderWindowOpen=transmitRepeats==0 && remainingPreambles<10 && remainingPreambles>1;
if (remainingPreambles==1)
promotePendingPacket();
#if defined(HAS_ENOUGH_MEMORY)
else if (isMainTrack && railcomActive) {
if (remainingPreambles==(requiredPreambles-1)) {
// First look if we need to start a railcom cutout on next interrupt
cutoutNextTime= true;
} else if (remainingPreambles==(requiredPreambles-12)) {
// cutout has ended so its now possible to poll the railcom detectors
// requiredPreambles is one higher that preamble length so
// if preamble length is 16 then this evaluates to 5
// Remember address bytes of last sent packet so that Railcom can
// work out where the channel2 data came from.
railcomLastAddressHigh=transmitPacket[0];
railcomLastAddressLow =transmitPacket[1];
railcomSampleWindow=true;
} else if (remainingPreambles==(requiredPreambles-3)) {
// cutout can be ended when read
// see above for requiredPreambles
DCCTimer::ackRailcomTimer();
}
}
#endif
reminderWindowOpen=transmitRepeats==0 && remainingPreambles<4 && remainingPreambles>1;
if (remainingPreambles==1) promotePendingPacket();
else if (remainingPreambles==10 && isMainTrack && railcomActive) DCCTimer::ackRailcomTimer();
// Update free memory diagnostic as we don't have anything else to do this time.
// Allow for checkAck and its called functions using 22 bytes more.
else DCCTimer::updateMinimumFreeMemoryISR(22);
@ -207,7 +171,13 @@ void DCCWaveform::interrupt2() {
bytes_sent = 0;
// preamble for next packet will start...
remainingPreambles = requiredPreambles;
}
// set the railcom coundown to trigger half way
// through the first preamble bit.
// Note.. we are still sending the last packet bit
// and we then have to allow for the packet end bit
if (isMainTrack && railcomActive) DCCTimer::startRailcomTimer(9);
}
}
}
#pragma GCC pop_options
@ -242,7 +212,7 @@ void DCCWaveform::promotePendingPacket() {
transmitRepeats--;
return;
}
if (packetPending) {
// Copy pending packet to transmit packet
// a fixed length memcpy is faster than a variable length loop for these small lengths
@ -260,7 +230,7 @@ void DCCWaveform::promotePendingPacket() {
// Fortunately reset and idle packets are the same length
// Note: If railcomDebug is on, then we send resets to the main
// track instead of idles. This means that all data will be zeros
// and only the presets will be ones, making it much
// and only the porersets will be ones, making it much
// easier to read on a logic analyser.
memcpy( transmitPacket, (isMainTrack && (!railcomDebug)) ? idlePacket : resetPacket, sizeof(idlePacket));
transmitLength = sizeof(idlePacket);
@ -268,3 +238,91 @@ void DCCWaveform::promotePendingPacket() {
if (getResets() < 250) sentResetsSincePacket++; // only place to increment (private!)
}
#endif
#ifdef ARDUINO_ARCH_ESP32
#include "DCCWaveform.h"
#include "DCCACK.h"
DCCWaveform DCCWaveform::mainTrack(PREAMBLE_BITS_MAIN, true);
DCCWaveform DCCWaveform::progTrack(PREAMBLE_BITS_PROG, false);
RMTChannel *DCCWaveform::rmtMainChannel = NULL;
RMTChannel *DCCWaveform::rmtProgChannel = NULL;
DCCWaveform::DCCWaveform(byte preambleBits, bool isMain) {
isMainTrack = isMain;
requiredPreambles = preambleBits;
}
void DCCWaveform::begin() {
for(const auto& md: TrackManager::getMainDrivers()) {
pinpair p = md->getSignalPin();
if(rmtMainChannel) {
//DIAG(F("added pins %d %d to MAIN channel"), p.pin, p.invpin);
rmtMainChannel->addPin(p); // add pin to existing main channel
} else {
//DIAG(F("new MAIN channel with pins %d %d"), p.pin, p.invpin);
rmtMainChannel = new RMTChannel(p, true); /* create new main channel */
}
}
MotorDriver *md = TrackManager::getProgDriver();
if (md) {
pinpair p = md->getSignalPin();
if (rmtProgChannel) {
//DIAG(F("added pins %d %d to PROG channel"), p.pin, p.invpin);
rmtProgChannel->addPin(p); // add pin to existing prog channel
} else {
//DIAG(F("new PROGchannel with pins %d %d"), p.pin, p.invpin);
rmtProgChannel = new RMTChannel(p, false);
}
}
}
void DCCWaveform::schedulePacket(const byte buffer[], byte byteCount, byte repeats) {
if (byteCount > MAX_PACKET_SIZE) return; // allow for chksum
RMTChannel *rmtchannel = (isMainTrack ? rmtMainChannel : rmtProgChannel);
if (rmtchannel == NULL)
return; // no idea to prepare packet if we can not send it anyway
rmtchannel->waitForDataCopy(); // blocking wait so we can write into buffer
byte checksum = 0;
for (byte b = 0; b < byteCount; b++) {
checksum ^= buffer[b];
pendingPacket[b] = buffer[b];
}
// buffer is MAX_PACKET_SIZE but pendingPacket is one bigger
pendingPacket[byteCount] = checksum;
pendingLength = byteCount + 1;
pendingRepeats = repeats;
// DIAG repeated commands (accesories)
// if (pendingRepeats > 0)
// DIAG(F("Repeats=%d on %s track"), pendingRepeats, isMainTrack ? "MAIN" : "PROG");
// The resets will be zero not only now but as well repeats packets into the future
clearResets(repeats+1);
{
int ret = 0;
do {
ret = rmtchannel->RMTfillData(pendingPacket, pendingLength, pendingRepeats);
} while(ret > 0);
}
}
bool DCCWaveform::isReminderWindowOpen() {
if(isMainTrack) {
if (rmtMainChannel == NULL)
return false;
return !rmtMainChannel->busy();
} else {
if (rmtProgChannel == NULL)
return false;
return !rmtProgChannel->busy();
}
}
void IRAM_ATTR DCCWaveform::loop() {
DCCACK::checkAck(progTrack.getResets());
}
bool DCCWaveform::setRailcom(bool on, bool debug) {
// TODO... ESP32 railcom waveform
return false;
}
#endif

View File

@ -3,7 +3,7 @@
* © 2021 Mike S
* © 2021 Fred Decker
* © 2020-2024 Harald Barth
* © 2020-2025 Chris Harlow
* © 2020-2021 Chris Harlow
* All rights reserved.
*
* This file is part of CommandStation-EX
@ -23,8 +23,11 @@
*/
#ifndef DCCWaveform_h
#define DCCWaveform_h
#include "MotorDriver.h"
#ifdef ARDUINO_ARCH_ESP32
#include "DCCRMT.h"
#include "TrackManager.h"
#endif
@ -83,30 +86,8 @@ class DCCWaveform {
bool isReminderWindowOpen();
void promotePendingPacket();
static bool setRailcom(bool on, bool debug);
inline static bool isRailcom() {
return railcomActive;
};
inline static byte getRailcomCutoutCounter() {
return railcomCutoutCounter;
};
inline static bool isRailcomSampleWindow() {
return railcomSampleWindow;
};
inline static bool isRailcomPossible() {
return railcomPossible;
};
inline static void setRailcomPossible(bool yes) {
railcomPossible=yes;
if (!yes) setRailcom(false,false);
};
inline static uint16_t getRailcomLastLocoAddress() {
// first 2 bits 00=short loco, 11=long loco , 01/10 = accessory
byte addressType=railcomLastAddressHigh & 0xC0;
if (addressType==0xC0) return ((railcomLastAddressHigh & 0x3f)<<8) | railcomLastAddressLow;
if (addressType==0x00) return railcomLastAddressHigh & 0x3F;
return 0;
}
static bool isRailcom() {return railcomActive;}
private:
#ifndef ARDUINO_ARCH_ESP32
volatile bool packetPending;
@ -131,13 +112,9 @@ class DCCWaveform {
byte pendingPacket[MAX_PACKET_SIZE+1]; // +1 for checksum
byte pendingLength;
byte pendingRepeats;
static bool railcomPossible; // High accuracy mode only
static volatile bool railcomActive; // switched on by user
static volatile bool railcomDebug; // switched on by user
static volatile bool railcomSampleWindow; // when safe to sample
static volatile byte railcomCutoutCounter; // incremented for each cutout
static volatile byte railcomLastAddressHigh,railcomLastAddressLow;
static bool cutoutNextTime; // railcom
#ifdef ARDUINO_ARCH_ESP32
static RMTChannel *rmtMainChannel;
static RMTChannel *rmtProgChannel;

View File

@ -1,120 +0,0 @@
/*
* © 2021 Neil McKechnie
* © 2021 Mike S
* © 2021 Fred Decker
* © 2020-2022 Harald Barth
* © 2020-2021 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/>.
*/
// This code is ESP32 ONLY.
#ifdef ARDUINO_ARCH_ESP32
#include "DCCWaveform.h"
#include "DCCACK.h"
#include "TrackManager.h"
DCCWaveform DCCWaveform::mainTrack(PREAMBLE_BITS_MAIN, true);
DCCWaveform DCCWaveform::progTrack(PREAMBLE_BITS_PROG, false);
RMTChannel *DCCWaveform::rmtMainChannel = NULL;
RMTChannel *DCCWaveform::rmtProgChannel = NULL;
bool DCCWaveform::railcomPossible=false; // High accuracy only
volatile bool DCCWaveform::railcomActive=false; // switched on by user
volatile bool DCCWaveform::railcomDebug=false; // switched on by user
volatile bool DCCWaveform::railcomSampleWindow=false; // true during packet transmit
volatile byte DCCWaveform::railcomCutoutCounter=0; // cyclic cutout
volatile byte DCCWaveform::railcomLastAddressHigh=0;
volatile byte DCCWaveform::railcomLastAddressLow=0;
DCCWaveform::DCCWaveform(byte preambleBits, bool isMain) {
isMainTrack = isMain;
requiredPreambles = preambleBits;
}
void DCCWaveform::begin() {
for(const auto& md: TrackManager::getMainDrivers()) {
pinpair p = md->getSignalPin();
if(rmtMainChannel) {
//DIAG(F("added pins %d %d to MAIN channel"), p.pin, p.invpin);
rmtMainChannel->addPin(p); // add pin to existing main channel
} else {
//DIAG(F("new MAIN channel with pins %d %d"), p.pin, p.invpin);
rmtMainChannel = new RMTChannel(p, true); /* create new main channel */
}
}
MotorDriver *md = TrackManager::getProgDriver();
if (md) {
pinpair p = md->getSignalPin();
if (rmtProgChannel) {
//DIAG(F("added pins %d %d to PROG channel"), p.pin, p.invpin);
rmtProgChannel->addPin(p); // add pin to existing prog channel
} else {
//DIAG(F("new PROGchannel with pins %d %d"), p.pin, p.invpin);
rmtProgChannel = new RMTChannel(p, false);
}
}
}
void DCCWaveform::schedulePacket(const byte buffer[], byte byteCount, byte repeats) {
if (byteCount > MAX_PACKET_SIZE) return; // allow for chksum
RMTChannel *rmtchannel = (isMainTrack ? rmtMainChannel : rmtProgChannel);
if (rmtchannel == NULL)
return; // no idea to prepare packet if we can not send it anyway
rmtchannel->waitForDataCopy(); // blocking wait so we can write into buffer
byte checksum = 0;
for (byte b = 0; b < byteCount; b++) {
checksum ^= buffer[b];
pendingPacket[b] = buffer[b];
}
// buffer is MAX_PACKET_SIZE but pendingPacket is one bigger
pendingPacket[byteCount] = checksum;
pendingLength = byteCount + 1;
pendingRepeats = repeats;
// DIAG repeated commands (accesories)
// if (pendingRepeats > 0)
// DIAG(F("Repeats=%d on %s track"), pendingRepeats, isMainTrack ? "MAIN" : "PROG");
// The resets will be zero not only now but as well repeats packets into the future
clearResets(repeats+1);
{
int ret = 0;
do {
ret = rmtchannel->RMTfillData(pendingPacket, pendingLength, pendingRepeats);
} while(ret > 0);
}
}
bool DCCWaveform::isReminderWindowOpen() {
if(isMainTrack) {
if (rmtMainChannel == NULL)
return false;
return !rmtMainChannel->busy();
} else {
if (rmtProgChannel == NULL)
return false;
return !rmtProgChannel->busy();
}
}
void IRAM_ATTR DCCWaveform::loop() {
DCCACK::checkAck(progTrack.getResets());
}
bool DCCWaveform::setRailcom(bool on, bool debug) {
// TODO... ESP32 railcom waveform
return false;
}
#endif

View File

@ -2,7 +2,7 @@
* © 2024 Paul M. Antoine
* © 2021 Neil McKechnie
* © 2021-2023 Harald Barth
* © 2020-2025 Chris Harlow
* © 2020-2023 Chris Harlow
* © 2022-2023 Colin Murdoch
* © 2025 Morten Nielsen
* All rights reserved.
@ -88,8 +88,6 @@ LookList * RMFT2::onClockLookup=NULL;
LookList * RMFT2::onRotateLookup=NULL;
#endif
LookList * RMFT2::onOverloadLookup=NULL;
LookList * RMFT2::onBlockEnterLookup=NULL;
LookList * RMFT2::onBlockExitLookup=NULL;
byte * RMFT2::routeStateArray=nullptr;
const FSH * * RMFT2::routeCaptionArray=nullptr;
int16_t * RMFT2::stashArray=nullptr;
@ -134,11 +132,11 @@ int16_t LookList::find(int16_t value) {
void LookList::chain(LookList * chain) {
m_chain=chain;
}
void LookList::handleEvent(const FSH* reason,int16_t id, int16_t loco) {
void LookList::handleEvent(const FSH* reason,int16_t id) {
// New feature... create multiple ONhandlers
for (int i=0;i<m_size;i++)
if (m_lookupArray[i]==id)
RMFT2::startNonRecursiveTask(reason,id,m_resultArray[i],loco);
RMFT2::startNonRecursiveTask(reason,id,m_resultArray[i]);
}
@ -206,12 +204,6 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
onRotateLookup=LookListLoader(OPCODE_ONROTATE);
#endif
onOverloadLookup=LookListLoader(OPCODE_ONOVERLOAD);
if (compileFeatures & FEATURE_BLOCK) {
onBlockEnterLookup=LookListLoader(OPCODE_ONBLOCKENTER);
onBlockExitLookup=LookListLoader(OPCODE_ONBLOCKEXIT);
}
// onLCCLookup is not the same so not loaded here.
// Second pass startup, define any turnouts or servos, set signals red
@ -388,7 +380,7 @@ char RMFT2::getRouteType(int16_t id) {
}
RMFT2::RMFT2(int progCtr, int16_t _loco) {
RMFT2::RMFT2(int progCtr) {
progCounter=progCtr;
// get an unused task id from the flags table
@ -401,7 +393,9 @@ RMFT2::RMFT2(int progCtr, int16_t _loco) {
}
}
delayTime=0;
loco=_loco;
loco=0;
speedo=0;
forward=true;
invert=false;
blinkState=not_blink_task;
stackDepth=0;
@ -419,10 +413,7 @@ RMFT2::RMFT2(int progCtr, int16_t _loco) {
RMFT2::~RMFT2() {
// estop my loco if this is not an ONevent
// (prevents DONE stopping loco at the end of an
// ONBLOCKENTER or ONBLOCKEXIT )
if (loco>0 && this->onEventStartPosition==-1) DCC::setThrottle(loco,1,DCC::getThrottleDirection(loco));
driveLoco(1); // ESTOP my loco if any
setFlag(taskId,0,TASK_FLAG); // we are no longer using this id
if (next==this)
loopTask=NULL;
@ -438,9 +429,23 @@ RMFT2::~RMFT2() {
void RMFT2::createNewTask(int route, uint16_t cab) {
int pc=routeLookup->find(route);
if (pc<0) return;
new RMFT2(pc,cab);
RMFT2* task=new RMFT2(pc);
task->loco=cab;
}
void RMFT2::driveLoco(byte speed) {
if (loco<=0) return; // Prevent broadcast!
//if (diag) DIAG(F("EXRAIL drive %d %d %d"),loco,speed,forward^invert);
/* TODO.....
power on appropriate track if DC or main if dcc
if (TrackManager::getMainPowerMode()==POWERMODE::OFF) {
TrackManager::setMainPower(POWERMODE::ON);
}
**********/
DCC::setThrottle(loco,speed, forward^invert);
speedo=speed;
}
bool RMFT2::readSensor(uint16_t sensorId) {
// Exrail operands are unsigned but we need the signed version as inserted by the macros.
@ -495,7 +500,7 @@ bool RMFT2::skipIfBlock() {
if (cv & LONG_ADDR_MARKER) { // maker bit indicates long addr
progtrackLocoId = cv ^ LONG_ADDR_MARKER; // remove marker bit to get real long addr
if (progtrackLocoId <= HIGHEST_SHORT_ADDR ) { // out of range for long addr
DIAG(F("Long addr %d <= %d unsupported\n"), progtrackLocoId, HIGHEST_SHORT_ADDR);
DIAG(F("Long addr %d <= %d unsupported"), progtrackLocoId, HIGHEST_SHORT_ADDR);
progtrackLocoId = -1;
}
} else {
@ -503,15 +508,6 @@ bool RMFT2::skipIfBlock() {
}
}
void RMFT2::pause() {
if (loco)
pauseSpeed=DCC::getThrottleSpeedByte(loco);
}
void RMFT2::resume() {
if (loco)
DCC::setThrottle(loco,pauseSpeed & 0x7f, pauseSpeed & 0x80);
}
void RMFT2::loop() {
if (compileFeatures & FEATURE_SENSOR)
EXRAILSensor::checkAll();
@ -576,23 +572,18 @@ void RMFT2::loop2() {
#endif
case OPCODE_REV:
if (loco) DCC::setThrottle(loco,operand,invert);
forward = false;
driveLoco(operand);
break;
case OPCODE_FWD:
if (loco) DCC::setThrottle(loco,operand,!invert);
break;
forward = true;
driveLoco(operand);
break;
case OPCODE_SPEED:
if (loco) DCC::setThrottle(loco,operand,DCC::getThrottleDirection(loco));
break;
case OPCODE_MOMENTUM:
DCC::setMomentum(loco,operand,getOperand(1));
break;
case OPCODE_ESTOPALL:
DCC::setThrottle(0,1,1); // all locos speed=1
forward=DCC::getThrottleDirection(loco)^invert;
driveLoco(operand);
break;
case OPCODE_FORGET:
@ -604,11 +595,12 @@ void RMFT2::loop2() {
case OPCODE_INVERT_DIRECTION:
invert= !invert;
driveLoco(speedo);
break;
case OPCODE_RESERVE:
if (getFlag(operand,SECTION_FLAG)) {
if (loco) DCC::setThrottle(loco,1,DCC::getThrottleDirection(loco));
driveLoco(0);
delayMe(500);
return;
}
@ -707,7 +699,7 @@ void RMFT2::loop2() {
break;
case OPCODE_PAUSE:
DCC::estopAll(); // pause all locos on the track
DCC::setThrottle(0,1,true); // pause all locos on the track
pausingTask=this;
break;
@ -715,10 +707,6 @@ void RMFT2::loop2() {
if (loco) DCC::writeCVByteMain(loco, operand, getOperand(1));
break;
case OPCODE_XPOM:
DCC::writeCVByteMain(operand, getOperand(1), getOperand(2));
break;
case OPCODE_POWEROFF:
TrackManager::setPower(POWERMODE::OFF);
TrackManager::setJoin(false);
@ -755,8 +743,8 @@ void RMFT2::loop2() {
case OPCODE_RESUME:
pausingTask=NULL;
resume();
for (RMFT2 * t=next; t!=this;t=t->next) t->resume();
driveLoco(speedo);
for (RMFT2 * t=next; t!=this;t=t->next) if (t->loco >0) t->driveLoco(t->speedo);
break;
case OPCODE_IF: // do next operand if sensor set
@ -867,7 +855,8 @@ void RMFT2::loop2() {
case OPCODE_DRIVE:
{
// Non functional but reserved
byte analogSpeed=IODevice::readAnalogue(operand) *127 / 1024;
if (speedo!=analogSpeed) driveLoco(analogSpeed);
break;
}
@ -942,8 +931,9 @@ void RMFT2::loop2() {
#ifndef DISABLE_PROG
case OPCODE_JOIN:
TrackManager::setPower(POWERMODE::ON);
TrackManager::setJoin(true);
TrackManager::setMainPower(POWERMODE::ON);
TrackManager::setProgPower(POWERMODE::ON);
break;
case OPCODE_UNJOIN:
@ -965,6 +955,8 @@ void RMFT2::loop2() {
// which is intended so it can be checked
// from within EXRAIL
loco=progtrackLocoId;
speedo=0;
forward=true;
invert=false;
break;
#endif
@ -986,13 +978,16 @@ void RMFT2::loop2() {
{
int newPc=routeLookup->find(getOperand(1));
if (newPc<0) break;
new RMFT2(newPc,operand); // create new task
RMFT2* newtask=new RMFT2(newPc); // create new task
newtask->loco=operand;
}
break;
case OPCODE_SETLOCO:
{
loco=operand;
speedo=0;
forward=true;
invert=false;
}
break;
@ -1126,8 +1121,7 @@ void RMFT2::loop2() {
case OPCODE_ONROTATE:
#endif
case OPCODE_ONOVERLOAD:
case OPCODE_ONBLOCKENTER:
case OPCODE_ONBLOCKEXIT:
break;
default:
@ -1319,14 +1313,6 @@ void RMFT2::activateEvent(int16_t addr, bool activate) {
else onDeactivateLookup->handleEvent(F("DEACTIVATE"),addr);
}
void RMFT2::blockEvent(int16_t block, int16_t loco, bool entering) {
if (compileFeatures & FEATURE_BLOCK) {
// Hunt for an ONBLOCKENTER/ONBLOCKEXIT for this accessory
if (entering) onBlockEnterLookup->handleEvent(F("BLOCKENTER"),block,loco);
else onBlockExitLookup->handleEvent(F("BLOCKEXIT"),block,loco);
}
}
void RMFT2::changeEvent(int16_t vpin, bool change) {
// Hunt for an ONCHANGE for this sensor
if (change) onChangeLookup->handleEvent(F("CHANGE"),vpin);
@ -1382,11 +1368,11 @@ void RMFT2::killBlinkOnVpin(VPIN pin, uint16_t count) {
}
}
void RMFT2::startNonRecursiveTask(const FSH* reason, int16_t id,int pc, uint16_t loco) {
void RMFT2::startNonRecursiveTask(const FSH* reason, int16_t id,int pc) {
// Check we dont already have a task running this handler
RMFT2 * task=loopTask;
while(task) {
if (task->onEventStartPosition==pc && task->loco==loco) {
if (task->onEventStartPosition==pc) {
DIAG(F("Recursive ON%S(%d)"),reason, id);
return;
}
@ -1394,7 +1380,7 @@ void RMFT2::startNonRecursiveTask(const FSH* reason, int16_t id,int pc, uint16_t
if (task==loopTask) break;
}
task=new RMFT2(pc,loco); // new task starts at this instruction
task=new RMFT2(pc); // new task starts at this instruction
task->onEventStartPosition=pc; // flag for recursion detector
}

View File

@ -1,6 +1,6 @@
/*
* © 2021 Neil McKechnie
* © 2020-2025 Chris Harlow
* © 2020-2022 Chris Harlow
* © 2022-2023 Colin Murdoch
* © 2023 Harald Barth
* © 2025 Morten Nielsen
@ -36,7 +36,6 @@
//
enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,OPCODE_TOGGLE_TURNOUT,
OPCODE_FWD,OPCODE_REV,OPCODE_SPEED,OPCODE_INVERT_DIRECTION,
OPCODE_MOMENTUM,
OPCODE_RESERVE,OPCODE_FREE,
OPCODE_AT,OPCODE_AFTER,
OPCODE_AFTEROVERLOAD,OPCODE_AUTOSTART,
@ -77,10 +76,8 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,OPCODE_TOGGLE_TURNOUT,
OPCODE_ROUTE_ACTIVE,OPCODE_ROUTE_INACTIVE,OPCODE_ROUTE_HIDDEN,
OPCODE_ROUTE_DISABLED,
OPCODE_STASH,OPCODE_CLEAR_STASH,OPCODE_CLEAR_ALL_STASH,OPCODE_PICKUP_STASH,
OPCODE_ONBUTTON,OPCODE_ONSENSOR,
OPCODE_ONBUTTON,OPCODE_ONSENSOR,
OPCODE_NEOPIXEL,
OPCODE_ONBLOCKENTER,OPCODE_ONBLOCKEXIT,
OPCODE_ESTOPALL,OPCODE_XPOM,
// OPcodes below this point are skip-nesting IF operations
// placed here so that they may be skipped as a group
// see skipIfBlock()
@ -140,7 +137,6 @@ enum SignalType {
static const byte FEATURE_STASH = 0x08;
static const byte FEATURE_BLINK = 0x04;
static const byte FEATURE_SENSOR = 0x02;
static const byte FEATURE_BLOCK = 0x01;
// Flag bits for status of hardware and TPL
@ -167,7 +163,7 @@ class LookList {
int16_t findPosition(int16_t value); // finds index
int16_t size();
void stream(Print * _stream);
void handleEvent(const FSH* reason,int16_t id, int16_t loco=0);
void handleEvent(const FSH* reason,int16_t id);
private:
int16_t m_size;
@ -181,7 +177,8 @@ class LookList {
public:
static void begin();
static void loop();
RMFT2(int progCounter, int16_t cab=0);
RMFT2(int progCounter);
RMFT2(int route, uint16_t cab);
~RMFT2();
static void readLocoCallback(int16_t cv);
static void createNewTask(int route, uint16_t cab);
@ -191,7 +188,6 @@ class LookList {
static void clockEvent(int16_t clocktime, bool change);
static void rotateEvent(int16_t id, bool change);
static void powerEvent(int16_t track, bool overload);
static void blockEvent(int16_t block, int16_t loco, bool entering);
static bool signalAspectEvent(int16_t address, byte aspect );
// Throttle Info Access functions built by exrail macros
static const byte rosterNameCount;
@ -205,7 +201,7 @@ class LookList {
static const FSH * getRosterFunctions(int16_t id);
static const FSH * getTurntableDescription(int16_t id);
static const FSH * getTurntablePositionDescription(int16_t turntableId, uint8_t positionId);
static void startNonRecursiveTask(const FSH* reason, int16_t id,int pc, uint16_t loco=0);
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);
static SIGNAL_DEFINITION getSignalSlot(int16_t slotno);
@ -229,6 +225,7 @@ private:
static RMFT2 * loopTask;
static RMFT2 * pausingTask;
void delayMe(long millisecs);
void driveLoco(byte speedo);
bool skipIfBlock();
bool readLoco();
void loop2();
@ -237,8 +234,6 @@ private:
void printMessage2(const FSH * msg);
void thrungeString(uint32_t strfar, thrunger mode, byte id=0);
uint16_t getOperand(byte n);
void pause();
void resume();
static bool diag;
static const HIGHFLASH3 byte RouteCode[];
@ -260,9 +255,6 @@ private:
static LookList * onRotateLookup;
#endif
static LookList * onOverloadLookup;
static LookList * onBlockEnterLookup;
static LookList * onBlockExitLookup;
static const int countLCCLookup;
static int onLCCLookup[];
@ -287,8 +279,9 @@ private:
byte taskId;
BlinkState blinkState; // includes AT_TIMEOUT flag.
uint16_t loco;
bool forward;
bool invert;
byte pauseSpeed;
byte speedo;
int onEventStartPosition;
byte stackDepth;
int callStack[MAX_STACK_DEPTH];

View File

@ -1,5 +1,5 @@
/*
* © 2020-2025 Chris Harlow. All rights reserved.
* © 2020-2022 Chris Harlow. All rights reserved.
* © 2022-2023 Colin Murdoch
* © 2023 Harald Barth
* © 2025 Morten Nielsen
@ -61,7 +61,6 @@
#undef ENDIF
#undef ENDTASK
#undef ESTOP
#undef ESTOPALL
#undef EXRAIL
#undef EXTT_TURNTABLE
#undef FADE
@ -100,7 +99,6 @@
#undef LCC
#undef LCCX
#undef LCN
#undef MOMENTUM
#undef MOVETT
#undef NEOPIXEL
#undef NEOPIXEL_OFF
@ -113,8 +111,6 @@
#undef ONACTIVATE
#undef ONACTIVATEL
#undef ONAMBER
#undef ONBLOCKENTER
#undef ONBLOCKEXIT
#undef ONDEACTIVATE
#undef ONDEACTIVATEL
#undef ONCLOSE
@ -199,7 +195,6 @@
#undef XFOFF
#undef XFON
#undef XFTOGGLE
#undef XPOM
#undef XREV
#undef XFWD
@ -222,7 +217,7 @@
#define BROADCAST(msg)
#define CALL(route)
#define CLEAR_STASH(id)
#define CLEAR_ALL_STASH(id)
#define CLEAR_ALL_STASH
#define CLOSE(id)
#define CONFIGURE_SERVO(vpin,pos1,pos2,profile)
#define DCC_SIGNAL(id,add,subaddr)
@ -240,7 +235,6 @@
#define ENDIF
#define ENDTASK
#define ESTOP
#define ESTOPALL
#define EXRAIL
#define EXTT_TURNTABLE(id,vpin,home,description...)
#define FADE(pin,value,ms)
@ -277,7 +271,6 @@
#define LCC(eventid)
#define LCCX(senderid,eventid)
#define LCD(row,msg)
#define MOMENTUM(accel,decel...)
#define SCREEN(display,row,msg)
#define LCN(msg)
#define MESSAGE(msg)
@ -291,8 +284,6 @@
#define ONACTIVATE(addr,subaddr)
#define ONACTIVATEL(linear)
#define ONAMBER(signal_id)
#define ONBLOCKENTER(blockid)
#define ONBLOCKEXIT(blockid)
#define ONTIME(value)
#define ONCLOCKTIME(hours,mins)
#define ONCLOCKMINS(mins)
@ -379,5 +370,5 @@
#define XFTOGGLE(cab,func)
#define XFWD(cab,speed)
#define XREV(cab,speed)
#define XPOM(cab,cv,value)
#endif

View File

@ -1,7 +1,7 @@
/*
* © 2021 Neil McKechnie
* © 2021-2023 Harald Barth
* © 2020-2025 Chris Harlow
* © 2020-2023 Chris Harlow
* © 2022-2023 Colin Murdoch
* All rights reserved.
*
@ -210,15 +210,6 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16
default:
break;
}
break;
case 'K': // <K blockid loco> Block enter
case 'k': // <k blockid loco> Block exit
if (paramCount!=2) break;
blockEvent(p[0],p[1],opcode=='K');
opcode=0;
break;
default: // other commands pass through
break;
}
@ -237,9 +228,11 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) {
);
}
else {
StringFormatter::send(stream,F("\nID=%d,PC=%d,LOCO=%d %c"),
StringFormatter::send(stream,F("\nID=%d,PC=%d,LOCO=%d%c,SPEED=%d%c"),
(int)(task->taskId),task->progCounter,task->loco,
task->invert?'I':' '
task->invert?'I':' ',
task->speedo,
task->forward?'F':'R'
);
}
task=task->next;
@ -283,27 +276,19 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) {
switch (p[0]) {
case "PAUSE"_hk: // </ PAUSE>
if (paramCount!=1) return false;
{ // pause all tasks
RMFT2 * task=loopTask;
while(task) {
task->pause();
task=task->next;
if (task==loopTask) break;
}
}
DCC::estopAll(); // pause all locos on the track
DCC::setThrottle(0,1,true); // pause all locos on the track
pausingTask=(RMFT2 *)1; // Impossible task address
return true;
case "RESUME"_hk: // </ RESUME>
if (paramCount!=1) return false;
pausingTask=NULL;
{ // resume all tasks
{
RMFT2 * task=loopTask;
while(task) {
task->resume();
task=task->next;
if (task==loopTask) break;
if (task->loco) task->driveLoco(task->speedo);
task=task->next;
if (task==loopTask) break;
}
}
return true;
@ -316,7 +301,8 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) {
uint16_t cab=(paramCount==2)? 0 : p[1];
int pc=routeLookup->find(route);
if (pc<0) return false;
new RMFT2(pc,cab);
RMFT2* task=new RMFT2(pc);
task->loco=cab;
}
return true;

View File

@ -1,6 +1,6 @@
/*
* © 2021 Neil McKechnie
* © 2020-2025 Chris Harlow
* © 2020-2022 Chris Harlow
* © 2022-2023 Colin Murdoch
* © 2023 Harald Barth
* © 2025 Morten Nielsen
@ -24,7 +24,6 @@
#ifndef EXRAILMacros_H
#define EXRAILMacros_H
#include "IODeviceList.h"
// remove normal code LCD & SERIAL macros (will be restored later)
#undef LCD
@ -232,10 +231,6 @@ bool exrailHalSetup() {
#define ONBUTTON(vpin) | FEATURE_SENSOR
#undef ONSENSOR
#define ONSENSOR(vpin) | FEATURE_SENSOR
#undef ONBLOCKENTER
#define ONBLOCKENTER(blockid) | FEATURE_BLOCK
#undef ONBLOCKEXIT
#define ONBLOCKEXIT(blockid) | FEATURE_BLOCK
const byte RMFT2::compileFeatures = 0
#include "myAutomation.h"
@ -518,7 +513,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define ENDIF OPCODE_ENDIF,0,0,
#define ENDTASK OPCODE_ENDTASK,0,0,
#define ESTOP OPCODE_SPEED,V(1),
#define ESTOPALL OPCODE_ESTOPALL,0,0,
#define EXRAIL
#ifndef IO_NO_HAL
#define EXTT_TURNTABLE(id,vpin,home,description...) OPCODE_EXTTTURNTABLE,V(id),OPCODE_PAD,V(vpin),OPCODE_PAD,V(home),
@ -571,7 +565,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define STEALTH_GLOBAL(code...)
#define LCN(msg) PRINT(msg)
#define MESSAGE(msg) PRINT(msg)
#define MOMENTUM(accel,decel...) OPCODE_MOMENTUM,V(accel),OPCODE_PAD,V(#decel[0]?decel+0:accel),
#define MOVETT(id,steps,activity) OPCODE_SERVO,V(id),OPCODE_PAD,V(steps),OPCODE_PAD,V(EXTurntable::activity),OPCODE_PAD,V(0),
#define NEOPIXEL(id,r,g,b,count...) OPCODE_NEOPIXEL,V(id),\
OPCODE_PAD,V(((r & 0xff)<<8) | (g & 0xff)),\
@ -582,8 +575,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define ONACTIVATE(addr,subaddr) OPCODE_ONACTIVATE,V(addr<<2|subaddr),
#define ONACTIVATEL(linear) OPCODE_ONACTIVATE,V(linear+3),
#define ONAMBER(signal_id) OPCODE_ONAMBER,V(signal_id),
#define ONBLOCKENTER(block_id) OPCODE_ONBLOCKENTER,V(block_id),
#define ONBLOCKEXIT(block_id) OPCODE_ONBLOCKEXIT,V(block_id),
#define ONCLOSE(turnout_id) OPCODE_ONCLOSE,V(turnout_id),
#define ONLCC(sender,event) OPCODE_ONLCC,V(event),\
OPCODE_PAD,V((((uint64_t)sender)>>32)&0xFFFF),\
@ -677,7 +668,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define XFTOGGLE(cab,func) OPCODE_XFTOGGLE,V(cab),OPCODE_PAD,V(func),
#define XFWD(cab,speed) OPCODE_XFWD,V(cab),OPCODE_PAD,V(speed),
#define XREV(cab,speed) OPCODE_XREV,V(cab),OPCODE_PAD,V(speed),
#define XPOM(cab,cv,value) OPCODE_XPOM,V(cab),OPCODE_PAD,V(cv),OPCODE_PAD,V(value),
// Build RouteCode
const int StringMacroTracker2=__COUNTER__;

View File

@ -1,200 +0,0 @@
/*
* © 2024 Harald Barth
* © 2024 Paul M. Antoine
* 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/>.
*/
#include <Arduino.h>
#include "EthernetInterface.h"
#ifdef DO_MDNS
#include "EXmDNS.h"
// fixed values for mDNS
static IPAddress mdnsMulticastIPAddr = IPAddress(224, 0, 0, 251);
#define MDNS_SERVER_PORT 5353
// dotToLen()
// converts stings of form ".foo.barbar.x" to a string with the
// dots replaced with lenght. So string above would result in
// "\x03foo\x06barbar\x01x" in C notation. If not NULL, *substr
// will point to the beginning of the last component, in this
// example that would be "\x01x".
//
static void dotToLen(char *str, char **substr) {
char *dotplace = NULL;
char *s;
byte charcount = 0;
for (s = str;/*see break*/ ; s++) {
if (*s == '.' || *s == '\0') {
// take care of accumulated
if (dotplace != NULL && charcount != 0) {
*dotplace = charcount;
}
if (*s == '\0')
break;
if (substr && *s == '.')
*substr = s;
// set new values
dotplace = s;
charcount = 0;
} else {
charcount++;
}
}
}
MDNS::MDNS(EthernetUDP& udp) {
_udp = &udp;
}
MDNS::~MDNS() {
_udp->stop();
if (_name) free(_name);
if (_serviceName) free(_serviceName);
if (_serviceProto) free(_serviceProto);
}
int MDNS::begin(const IPAddress& ip, char* name) {
// if we were called very soon after the board was booted, we need to give the
// EthernetShield (WIZnet) some time to come up. Hence, we delay until millis() is at
// least 3000. This is necessary, so that if we need to add a service record directly
// after begin, the announce packet does not get lost in the bowels of the WIZnet chip.
//while (millis() < 3000)
// delay(100);
_ipAddress = ip;
_name = (char *)malloc(strlen(name)+2);
byte n;
for(n = 0; n<strlen(name); n++)
_name[n+1] = name[n];
_name[n+1] = '\0';
_name[0] = '.';
dotToLen(_name, NULL);
return _udp->beginMulticast(mdnsMulticastIPAddr, MDNS_SERVER_PORT);
}
int MDNS::addServiceRecord(const char* name, uint16_t port, MDNSServiceProtocol_t proto) {
// we ignore proto, assume TCP
(void)proto;
_serviceName = (char *)malloc(strlen(name) + 2);
byte n;
for(n = 0; n<strlen(name); n++)
_serviceName[n+1] = name[n];
_serviceName[n+1] = '\0';
_serviceName[0] = '.';
_serviceProto = NULL; //to be filled in
dotToLen(_serviceName, &_serviceProto);
_servicePort = port;
return 1;
}
static char dns_rr_services[] = "\x09_services\x07_dns-sd\x04_udp\x05local";
static char dns_rr_tcplocal[] = "\x04_tcp\x05local";
static char *dns_rr_local = dns_rr_tcplocal + dns_rr_tcplocal[0] + 1;
typedef struct _DNSHeader_t
{
uint16_t xid;
uint16_t flags; // flags condensed
uint16_t queryCount;
uint16_t answerCount;
uint16_t authorityCount;
uint16_t additionalCount;
} __attribute__((__packed__)) DNSHeader_t;
//
// MDNS::run()
// This broadcasts whatever we got evey BROADCASTTIME seconds.
// Why? Too much brokenness i all mDNS implementations available
//
void MDNS::run() {
static long int lastrun = BROADCASTTIME * 1000UL;
unsigned long int now = millis();
if (!(now - lastrun > BROADCASTTIME * 1000UL)) {
return;
}
lastrun = now;
DNSHeader_t dnsHeader = {0, 0, 0, 0, 0, 0};
// DNSHeader_t dnsHeader = { 0 };
_udp->beginPacket(mdnsMulticastIPAddr, MDNS_SERVER_PORT);
// dns header
dnsHeader.flags = HTONS((uint16_t)0x8400); // Response, authorative
dnsHeader.answerCount = HTONS(4 /*5 if TXT but we do not do that */);
_udp->write((uint8_t*)&dnsHeader, sizeof(DNSHeader_t));
// rr #1, the PTR record from generic _services.x.local to service.x.local
_udp->write((uint8_t*)dns_rr_services, sizeof(dns_rr_services));
byte buf[10];
buf[0] = 0x00;
buf[1] = 0x0c; //PTR
buf[2] = 0x00;
buf[3] = 0x01; //IN
*((uint32_t*)(buf+4)) = HTONL(120); //TTL in sec
*((uint16_t*)(buf+8)) = HTONS( _serviceProto[0] + 1 + strlen(dns_rr_tcplocal) + 1);
_udp->write(buf, 10);
_udp->write(_serviceProto,_serviceProto[0]+1);
_udp->write(dns_rr_tcplocal, strlen(dns_rr_tcplocal)+1);
// rr #2, the PTR record from proto.x to name.proto.x
_udp->write(_serviceProto,_serviceProto[0]+1);
_udp->write(dns_rr_tcplocal, strlen(dns_rr_tcplocal)+1);
*((uint16_t*)(buf+8)) = HTONS(strlen(_serviceName) + strlen(dns_rr_tcplocal) + 1); // recycle most of buf
_udp->write(buf, 10);
_udp->write(_serviceName, strlen(_serviceName));
_udp->write(dns_rr_tcplocal, strlen(dns_rr_tcplocal)+1);
// rr #3, the SRV record for the service that points to local name
_udp->write(_serviceName, strlen(_serviceName));
_udp->write(dns_rr_tcplocal, strlen(dns_rr_tcplocal)+1);
buf[1] = 0x21; // recycle most of buf but here SRV
buf[2] = 0x80; // cache flush
*((uint16_t*)(buf+8)) = HTONS(strlen(_name) + strlen(dns_rr_local) + 1 + 6);
_udp->write(buf, 10);
byte srv[6];
// priority and weight
srv[0] = srv[1] = srv[2] = srv[3] = 0;
// port
*((uint16_t*)(srv+4)) = HTONS(_servicePort);
_udp->write(srv, 6);
// target
_udp->write(_name, _name[0]+1);
_udp->write(dns_rr_local, strlen(dns_rr_local)+1);
// rr #4, the A record for the name.local
_udp->write(_name, _name[0]+1);
_udp->write(dns_rr_local, strlen(dns_rr_local)+1);
buf[1] = 0x01; // recycle most of buf but here A
*((uint16_t*)(buf+8)) = HTONS(4);
_udp->write(buf, 10);
byte ip[4];
ip[0] = _ipAddress[0];
ip[1] = _ipAddress[1];
ip[2] = _ipAddress[2];
ip[3] = _ipAddress[3];
_udp->write(ip, 4);
_udp->endPacket();
_udp->flush();
//
}
#endif //DO_MDNS

View File

@ -1,50 +0,0 @@
/*
* © 2024 Harald Barth
* © 2024 Paul M. Antoine
* 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/>.
*/
#ifdef DO_MDNS
#define BROADCASTTIME 15 //seconds
// We do this ourselves because every library is different and/or broken...
#define HTONS(x) ((uint16_t)(((x) << 8) | (((x) >> 8) & 0xFF)))
#define HTONL(x) ( ((uint32_t)(x) << 24) | (((uint32_t)(x) << 8) & 0xFF0000) | \
(((uint32_t)(x) >> 8) & 0xFF00) | ((uint32_t)(x) >> 24) )
typedef enum _MDNSServiceProtocol_t
{
MDNSServiceTCP,
MDNSServiceUDP
} MDNSServiceProtocol_t;
class MDNS {
public:
MDNS(EthernetUDP& udp);
~MDNS();
int begin(const IPAddress& ip, char* name);
int addServiceRecord(const char* name, uint16_t port, MDNSServiceProtocol_t proto);
void run();
private:
EthernetUDP *_udp;
IPAddress _ipAddress;
char* _name;
char* _serviceName;
char* _serviceProto;
int _servicePort;
};
#endif //DO_MDNS

View File

@ -31,13 +31,14 @@
#include "CommandDistributor.h"
#include "WiThrottle.h"
#include "DCCTimer.h"
#ifdef DO_MDNS
#include "EXmDNS.h"
EthernetUDP udp;
MDNS mdns(udp);
#if __has_include ( "MDNS_Generic.h")
#include "MDNS_Generic.h"
#define DO_MDNS
EthernetUDP udp;
MDNS mdns(udp);
#endif
//extern void looptimer(unsigned long timeout, const FSH* message);
#define looptimer(a,b)
@ -115,10 +116,10 @@ void EthernetInterface::setup()
outboundRing=new RingStream(OUTBOUND_RING_SIZE);
#ifdef DO_MDNS
if (!mdns.begin(Ethernet.localIP(), (char *)WIFI_HOSTNAME))
DIAG(F("mdns.begin fail")); // hostname
mdns.begin(Ethernet.localIP(), WIFI_HOSTNAME); // hostname
mdns.addServiceRecord(WIFI_HOSTNAME "._withrottle", IP_PORT, MDNSServiceTCP);
mdns.run(); // run it right away to get out info ASAP
// Not sure if we need to run it once, but just in case!
mdns.run();
#endif
connected=true;
}
@ -143,9 +144,7 @@ void EthernetInterface::acceptClient() { // STM32 version
return;
}
}
// reached here only if more than MAX_SOCK_NUM clients want to connect
DIAG(F("Ethernet more than %d clients, not accepting new connection"), MAX_SOCK_NUM);
client.stop();
DIAG(F("Ethernet OVERFLOW"));
}
#else
void EthernetInterface::acceptClient() { // non-STM32 version

View File

@ -3,7 +3,7 @@
* © 2021 Neil McKechnie
* © 2021 Mike S
* © 2021 Fred Decker
* © 2020-2024 Harald Barth
* © 2020-2022 Harald Barth
* © 2020-2024 Chris Harlow
* © 2020 Gregor Baues
* All rights reserved.
@ -31,32 +31,24 @@
#define EthernetInterface_h
#include "defines.h"
#if ETHERNET_ON == true
#include "DCCEXParser.h"
#include <Arduino.h>
//#include <avr/pgmspace.h>
#if defined (ARDUINO_TEENSY41)
#include <NativeEthernet.h> //TEENSY Ethernet Treiber
#include <NativeEthernetUdp.h>
#ifndef MAX_SOCK_NUM
#define MAX_SOCK_NUM 4
#endif
// can't use our MDNS because of a namespace clash with Teensy's NativeEthernet library!
// #define DO_MDNS
#elif defined (ARDUINO_NUCLEO_F429ZI) || defined (ARDUINO_NUCLEO_F439ZI) || defined (ARDUINO_NUCLEO_F4X9ZI)
#include <LwIP.h>
// #include "STM32lwipopts.h"
#include <STM32Ethernet.h>
#include <lwip/netif.h>
extern "C" struct netif gnetif;
#define STM32_ETHERNET
#define MAX_SOCK_NUM MAX_NUM_TCP_CLIENTS
#define DO_MDNS
#define MAX_SOCK_NUM 8
#else
#include "Ethernet.h"
#define DO_MDNS
#endif
#include "RingStream.h"
/**
@ -85,5 +77,5 @@ class EthernetInterface {
static void dropClient(byte socketnum);
};
#endif // ETHERNET_ON
#endif

View File

@ -1 +1 @@
#define GITHUB_SHA "devel-202503022043Z"
#define GITHUB_SHA "c389fe9"

View File

@ -560,6 +560,18 @@ protected:
};
//#include "IODeviceList.h"
#include "IO_MCP23008.h"
#include "IO_MCP23017.h"
#include "IO_PCF8574.h"
#include "IO_PCF8575.h"
#include "IO_PCA9555.h"
#include "IO_duinoNodes.h"
#include "IO_EXIOExpander.h"
#include "IO_trainbrains.h"
#include "IO_EncoderThrottle.h"
#include "IO_TCA8418.h"
#include "IO_NeoPixel.h"
#include "IO_TM1638.h"
#include "IO_EXSensorCAM.h"
#endif // iodevice_h

View File

@ -1,38 +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/>.
*/
/*
This is the list of HAL drivers automatically included by IODevice.h
It has been moved here to be easier to maintain than editing IODevice.h
*/
#include "IO_MCP23008.h"
#include "IO_MCP23017.h"
#include "IO_PCF8574.h"
#include "IO_PCF8575.h"
#include "IO_PCA9555.h"
#include "IO_duinoNodes.h"
#include "IO_EXIOExpander.h"
#include "IO_trainbrains.h"
#include "IO_EncoderThrottle.h"
#include "IO_TCA8418.h"
#include "IO_NeoPixel.h"
#include "IO_TM1638.h"
#include "IO_EXSensorCAM.h"
#include "IO_DS1307.h"
#include "IO_I2CRailcom.h"

View File

@ -1,143 +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/>.
*/
/*
* The IO_DS1307 device driver is used to interface a standalone realtime clock.
* The clock will announce every minute (which will trigger EXRAIL ONTIME events).
* Seconds, and Day/date info is ignored, except that the announced hhmm time
* will attempt to synchronize with the 0 seconds of the clock.
* An analog read in EXRAIL (IFGTE(vpin, value) etc will check against the hh*60+mm time.
* The clock can be easily set by an analog write to the vpin using 24 hr clock time
* with the command <z vpin hh mm ss>
*/
#include "IO_DS1307.h"
#include "I2CManager.h"
#include "DIAG.h"
#include "CommandDistributor.h"
uint8_t d2b(uint8_t d) {
return (d >> 4)*10 + (d & 0x0F);
}
void DS1307::create(VPIN vpin, I2CAddress i2cAddress) {
if (checkNoOverlap(vpin, 1, i2cAddress)) new DS1307(vpin, i2cAddress);
}
// Constructor
DS1307::DS1307(VPIN vpin,I2CAddress i2cAddress){
_firstVpin = vpin;
_nPins = 1;
_I2CAddress = i2cAddress;
addDevice(this);
}
uint32_t DS1307::getTime() {
// Obtain ss,mm,hh buffers from device
uint8_t readBuffer[3];
const uint8_t writeBuffer[1]={0};
// address register 0 for read.
I2CManager.write(_I2CAddress, writeBuffer, 1);
if (I2CManager.read(_I2CAddress, readBuffer, 3) != I2C_STATUS_OK) {
_deviceState=DEVSTATE_FAILED;
return 0;
}
_deviceState=DEVSTATE_NORMAL;
if (debug) {
static const char hexchars[]="0123456789ABCDEF";
USB_SERIAL.print(F("<*RTC"));
for (int i=2;i>=0;i--) {
USB_SERIAL.write(' ');
USB_SERIAL.write(hexchars[readBuffer[i]>>4]);
USB_SERIAL.write(hexchars[readBuffer[i]& 0x0F ]);
}
StringFormatter::send(&USB_SERIAL,F(" %d *>\n"),_deviceState);
}
if (readBuffer[0] & 0x80) {
_deviceState=DEVSTATE_INITIALISING;
DIAG(F("DS1307 clock in standby"));
return 0; // clock is not running
}
// convert device format to seconds since midnight
uint8_t ss=d2b(readBuffer[0] & 0x7F);
uint8_t mm=d2b(readBuffer[1]);
uint8_t hh=d2b(readBuffer[2] & 0x3F);
return (hh*60ul +mm)*60ul +ss;
}
void DS1307::_begin() {
// Initialise device and sync loop() to zero seconds
I2CManager.begin();
auto tstamp=getTime();
if (_deviceState==DEVSTATE_NORMAL) {
byte seconds=tstamp%60;
delayUntil(micros() + ((60-seconds) * 1000000));
}
_display();
}
// Processing loop to obtain clock time.
// This self-synchronizes to the next minute tickover
void DS1307::_loop(unsigned long currentMicros) {
auto time=getTime();
if (_deviceState==DEVSTATE_NORMAL) {
byte ss=time%60;
CommandDistributor::setClockTime(time/60, 1, 1);
delayUntil(currentMicros + ((60-ss) * 1000000));
}
}
// Display device driver info.
void DS1307::_display() {
auto tstamp=getTime();
byte ss=tstamp%60;
tstamp/=60;
byte mm=tstamp%60;
byte hh=tstamp/60;
DIAG(F("DS1307 on I2C:%s vpin %d %d:%d:%d %S"),
_I2CAddress.toString(), _firstVpin,
hh,mm,ss,
(_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F(""));
}
// allow user to set the clock
void DS1307::_writeAnalogue(VPIN vpin, int hh, uint8_t mm, uint16_t ss) {
(void) vpin;
uint8_t writeBuffer[3];
writeBuffer[0]=1; // write mm,hh first
writeBuffer[1]=((mm/10)<<4) + (mm % 10);
writeBuffer[2]=((hh/10)<<4) + (hh % 10);
I2CManager.write(_I2CAddress, writeBuffer, 3);
writeBuffer[0]=0; // write ss
writeBuffer[1]=((ss/10)<<4) + (ss % 10);
I2CManager.write(_I2CAddress, writeBuffer, 2);
_loop(micros()); // resync with seconds rollover
}
// Method to read analogue hh*60+mm time
int DS1307::_readAnalogue(VPIN vpin) {
(void)vpin;
return getTime()/60;
};

View File

@ -1,54 +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/>.
*/
/*
* The IO_DS1307 device driver is used to interface a standalone realtime clock.
* The clock will announce every minute (which will trigger EXRAIL ONTIME events).
* Seconds, and Day/date info is ignored, except that the announced hhmm time
* will attempt to synchronize with the 0 seconds of the clock.
* An analog read in EXRAIL (IFGTE(vpin, value) etc will check against the hh*60+mm time.
* The clock can be easily set by an analog write to the vpin using 24 hr clock time
* with the command <z vpin hh mm ss>
*/
#ifndef IO_DS1307_h
#define IO_DS1307_h
#include "IODevice.h"
class DS1307 : public IODevice {
public:
static const bool debug=false;
static void create(VPIN vpin, I2CAddress i2cAddress);
private:
// Constructor
DS1307(VPIN vpin,I2CAddress i2cAddress);
uint32_t getTime();
void _begin() override;
void _display() override;
void _loop(unsigned long currentMicros) override;
int _readAnalogue(VPIN vpin) override;
void _writeAnalogue(VPIN vpin, int hh, uint8_t mm, uint16_t ss) override;
};
#endif

View File

@ -16,10 +16,7 @@
* You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/
#define driverVer 306
// v306 Pass vpin to regeister it in CamParser.
// Move base vpin to camparser.
// No more need for config.h settings.
#define driverVer 305
// v305 less debug & alpha ordered switch
// v304 static oldb0; t(##[,%%];
// v303 zipped with CS 5.2.76 and uploaded to repo (with debug)
@ -38,18 +35,23 @@
* This device driver will configure the device on startup, along with CamParser.cpp
* interacting with the sensorCAM device for all input/output duties.
*
* To create EX-SensorCAM devices,
* use HAL(EXSensorCAM, baseVpin, numpins, i2c_address) in myAutomation.h
* e.g.
* HAL(EXSensorCAM,700, 80, 0x11)
*
* or (deprecated) define them in myHal.cpp: with
* EXSensorCAM::create(baseVpin,num_vpins,i2c_address);
* #include "CamParser.h" in DCCEXParser.cpp
* #include "IO_EXSensorCAM.h" in IODevice.h
* To create EX-SensorCAM devices, define them in myHal.cpp: with
* EXSensorCAM::create(baseVpin,num_vpins,i2c_address) or
* alternatively use HAL(EXSensorCAM baseVpin numpins i2c_address) in myAutomation.h
* also #define SENSORCAM_VPIN baseVpin in config.h
*
* void halSetup() {
* // EXSensorCAM::create(vpin, num_vpins, i2c_address);
* EXSensorCAM::create(700, 80, 0x11);
* }
*
* I2C packet size of 32 bytes (in the Wire library).
*/
# define DIGITALREFRESH 20000UL // min uSec delay between digital reads of digitalInputStates
#ifndef IO_EX_EXSENSORCAM_H
#define IO_EX_EXSENSORCAM_H
#define DIGITALREFRESH 20000UL // min uSec delay between digital reads of digitalInputStates
#define SEND StringFormatter::send
#include "IODevice.h"
#include "I2CManager.h"
@ -68,7 +70,7 @@ class EXSensorCAM : public IODevice {
new EXSensorCAM(vpin, nPins, i2cAddress);
}
static VPIN CAMBaseVpin;
private:
// Constructor
@ -79,7 +81,6 @@ class EXSensorCAM : public IODevice {
_nPins = nPins;
_I2CAddress = i2cAddress;
addDevice(this);
CamParser::addVpin(firstVpin);
}
//*************************
void _begin() {

View File

@ -24,7 +24,6 @@
*/
#include "IODevice.h"
#include "IO_EncoderThrottle.h"
#include "DIAG.h"
#include "DCC.h"

View File

@ -511,7 +511,6 @@ public:
if (pin == 0) { // Do nothing if not vPin 0
return _playing;
}
return _playing; // fix for compile error: "control reaches end of non-void function [-Wreturn-type]"
}
void _display() override {
@ -550,8 +549,8 @@ private:
setChecksum(out);
// Prepend the DFPlayer command with REG address and UART Channel in _outbuffer
_outbuffer[0] = REG_THR << 3 | _UART_CH << 1; //TX FIFO and UART Channel
for ( uint8_t i = 1; i < sizeof(out)+1 ; i++){
_outbuffer[0] = REG_THR << 3 | _UART_CH << 1; //TX FIFO and UART Channel
for ( int i = 1; i < sizeof(out)+1 ; i++){
_outbuffer[i] = out[i-1];
}
@ -617,14 +616,6 @@ private:
uint16_t _divisor = (_sc16is752_xtal_freq/PRESCALER)/(BAUD_RATE * 16); // Calculate _divisor for baudrate
TEMP_REG_VAL = 0x08; // UART Software reset
UART_WriteRegister(REG_IOCONTROL, TEMP_REG_VAL);
// Extra delay when using low frequency xtal after soft reset
// Test when using 1.8432 Mhz xtal
if(_sc16is752_xtal_freq == SC16IS752_XTAL_FREQ_LOW){
_timeoutTime = micros() + 10000UL; // 10mS timeout
_awaitingResponse = true;
}
TEMP_REG_VAL = 0x00; // Set pins to GPIO mode
UART_WriteRegister(REG_IOCONTROL, TEMP_REG_VAL);
TEMP_REG_VAL = 0xFF; //Set all pins as output

View File

@ -1,303 +0,0 @@
/*
* © 2024, Henk Kruisbrink & Chris Harlow. All rights reserved.
* © 2023, Neil McKechnie. All rights reserved.
*
* This file is part of DCC++EX API
*
* This is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* 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/>.
*/
/*
*
* Dec 2023, Added NXP SC16IS752 I2C Dual UART
* The SC16IS752 has 64 bytes TX & RX FIFO buffer
* First version without interrupts from I2C UART and only RX/TX are used, interrupts may not be
* needed as the RX Fifo holds the reply
*
* Jan 2024, Issue with using both UARTs simultaniously, the secod uart seems to work but the first transmit
* corrupt data. This need more analysis and experimenatation.
* Will push this driver to the dev branch with the uart fixed to 0
* Both SC16IS750 (single uart) and SC16IS752 (dual uart, but only uart 0 is enable)
*
* myHall.cpp configuration syntax:
*
* I2CRailcom::create(1st vPin, vPins, I2C address);
*
* myAutomation configuration
* HAL(I2CRailcom, 1st vPin, vPins, I2C address)
* Parameters:
* 1st vPin : First virtual pin that EX-Rail can control to play a sound, use PLAYSOUND command (alias of ANOUT)
* vPins : Total number of virtual pins allocated (2 vPins are supported, one for each UART)
* 1st vPin for UART 0, 2nd for UART 1
* I2C Address : I2C address of the serial controller, in 0x format
*/
#include "IODevice.h"
#include "IO_I2CRailcom.h"
#include "I2CManager.h"
#include "DIAG.h"
#include "DCCWaveform.h"
#include "Railcom.h"
// Debug and diagnostic defines, enable too many will result in slowing the driver
#define DIAG_I2CRailcom
I2CRailcom::I2CRailcom(VPIN firstVpin, int nPins, I2CAddress i2cAddress){
_firstVpin = firstVpin;
_nPins = nPins;
_I2CAddress = i2cAddress;
_channelMonitors[0]=new Railcom(firstVpin);
if (nPins>1) _channelMonitors[1]=new Railcom(firstVpin+1);
addDevice(this);
}
void I2CRailcom::create(VPIN firstVpin, int nPins, I2CAddress i2cAddress) {
if (nPins>2) nPins=2;
if (checkNoOverlap(firstVpin, nPins, i2cAddress))
new I2CRailcom(firstVpin, nPins, i2cAddress);
}
void I2CRailcom::_begin() {
I2CManager.setClock(1000000); // TODO do we need this?
I2CManager.begin();
auto exists=I2CManager.exists(_I2CAddress);
DIAG(F("I2CRailcom: %s UART%S detected"),
_I2CAddress.toString(), exists?F(""):F(" NOT"));
if (!exists) return;
_UART_CH=0;
Init_SC16IS752(); // Initialize UART0
if (_nPins>1) {
_UART_CH=1;
Init_SC16IS752(); // Initialize UART1
}
if (_deviceState==DEVSTATE_INITIALISING) _deviceState=DEVSTATE_NORMAL;
_display();
}
void I2CRailcom::_loop(unsigned long currentMicros) {
// Read responses from device
if (_deviceState!=DEVSTATE_NORMAL) return;
// return if in cutout or cutout very soon.
if (!DCCWaveform::isRailcomSampleWindow()) return;
// IF we have 2 channels, flip channels each loop
if (_nPins>1) _UART_CH=_UART_CH?0:1;
// have we read this cutout already?
auto cut=DCCWaveform::getRailcomCutoutCounter();
if (cutoutCounter[_UART_CH]==cut) return;
cutoutCounter[_UART_CH]=cut;
// Read incoming raw Railcom data, and process accordingly
auto inlength = UART_ReadRegister(REG_RXLV);
if (inlength> sizeof(_inbuf)) inlength=sizeof(_inbuf);
_inbuf[0]=0;
if (inlength>0) {
// Read data buffer from UART
_outbuf[0]=(byte)(REG_RHR << 3 | _UART_CH << 1);
I2CManager.read(_I2CAddress, _inbuf, inlength, _outbuf, 1);
}
// HK: Reset FIFO at end of read cycle
UART_WriteRegister(REG_FCR, 0x07,false);
// Ask Railcom to interpret the raw data
_channelMonitors[_UART_CH]->process(_inbuf,inlength);
}
void I2CRailcom::_display() {
DIAG(F("I2CRailcom: Configured on Vpins:%u-%u %S"), _firstVpin, _firstVpin+_nPins-1,
(_deviceState!=DEVSTATE_NORMAL) ? F("OFFLINE") : F(""));
}
// SC16IS752 functions
// Initialise SC16IS752 only for this channel
// First a software reset
// Enable FIFO and clear TX & RX FIFO
// Need to set the following registers
// IOCONTROL set bit 1 and 2 to 0 indicating that they are GPIO
// IODIR set all bit to 1 indicating al are output
// IOSTATE set only bit 0 to 1 for UART 0, or only bit 1 for UART 1 //
// LCR bit 7=0 divisor latch (clock division registers DLH & DLL, they store 16 bit divisor),
// WORD_LEN, STOP_BIT, PARITY_ENA and PARITY_TYPE
// MCR bit 7=0 clock divisor devide-by-1 clock input
// DLH most significant part of divisor
// DLL least significant part of divisor
//
// BAUD_RATE, WORD_LEN, STOP_BIT, PARITY_ENA and PARITY_TYPE have been defined and initialized
//
// Communication parameters 8 bit, No parity, 1 stopbit
static const uint8_t WORD_LEN = 0x03; // Value LCR bit 0,1
static const uint8_t STOP_BIT = 0x00; // Value LCR bit 2
static const uint8_t PARITY_ENA = 0x00; // Value LCR bit 3
static const uint8_t PARITY_TYPE = 0x00; // Value LCR bit 4
static const uint32_t BAUD_RATE = 250000;
static const uint8_t PRESCALER = 0x01; // Value MCR bit 7
static const unsigned long SC16IS752_XTAL_FREQ_RAILCOM = 16000000; // Baud rate for Railcom signal
static const uint16_t _divisor = (SC16IS752_XTAL_FREQ_RAILCOM / PRESCALER) / (BAUD_RATE * 16);
void I2CRailcom::Init_SC16IS752(){
if (_UART_CH==0) { // HK: Currently fixed on ch 0
// only reset on channel 0}
UART_WriteRegister(REG_IOCONTROL, 0x08,false); // UART Software reset
//_deviceState=DEVSTATE_INITIALISING; // ignores error during reset which seems normal. // HK: this line is moved to below
auto iocontrol_readback = UART_ReadRegister(REG_IOCONTROL);
if (iocontrol_readback == 0x00){
_deviceState=DEVSTATE_INITIALISING;
DIAG(F("I2CRailcom: %s SRESET readback: 0x%x"),_I2CAddress.toString(), iocontrol_readback);
} else {
DIAG(F("I2CRailcom: %s SRESET: 0x%x"),_I2CAddress.toString(), iocontrol_readback);
}
}
// HK:
// You write 0x08 to the IOCONTROL register, setting bit 3 (SRESET), as per datasheet 8.18:
// "Software Reset. A write to this bit will reset the device. Once the
// device is reset this bit is automatically set to logic 0"
// So you can not readback the val you have written as this has changed.
// I've added an extra UART_ReadRegister(REG_IOCONTROL) and check if the return value is 0x00
// then set _deviceState=DEVSTATE_INITIALISING;
// HK: only do clear FIFO at end of Init_SC16IS752
//UART_WriteRegister(REG_FCR, 0x07,false); // Reset FIFO, clear RX & TX FIFO (write only)
UART_WriteRegister(REG_MCR, 0x00); // Set MCR to all 0, includes Clock divisor
//UART_WriteRegister(REG_LCR, 0x80); // Divisor latch enabled
UART_WriteRegister(REG_LCR, 0x80 | WORD_LEN | STOP_BIT | PARITY_ENA | PARITY_TYPE); // Divisor latch enabled and comm parameters set
UART_WriteRegister(REG_DLL, (uint8_t)_divisor); // Write DLL
UART_WriteRegister(REG_DLH, (uint8_t)(_divisor >> 8)); // Write DLH
auto lcr_readback = UART_ReadRegister(REG_LCR);
lcr_readback = lcr_readback & 0x7F;
UART_WriteRegister(REG_LCR, lcr_readback); // Divisor latch disabled
//UART_WriteRegister(REG_LCR, WORD_LEN | STOP_BIT | PARITY_ENA | PARITY_TYPE); // Divisor latch disabled
UART_WriteRegister(REG_FCR, 0x07,false); // Reset FIFO, clear RX & TX FIFO (write only)
#ifdef DIAG_I2CRailcom
// HK: Test to see if internal loopback works and if REG_RXLV increment to at least 0x01
// Set REG_MCR bit 4 to 1, Enable Loopback
UART_WriteRegister(REG_MCR, 0x10);
UART_WriteRegister(REG_THR, 0x88, false); // Send 0x88
auto inlen = UART_ReadRegister(REG_RXLV);
if (inlen == 0){
DIAG(F("I2CRailcom: Loopback test: %s/%d failed"),_I2CAddress.toString(), _UART_CH);
} else {
DIAG(F("Railcom: Loopback test: %s/%d RX Fifo lvl: 0x%x"),_I2CAddress.toString(), _UART_CH, inlen);
_outbuf[0]=(byte)(REG_RHR << 3 | _UART_CH << 1);
I2CManager.read(_I2CAddress, _inbuf, inlen, _outbuf, 1);
#ifdef DIAG_I2CRailcom_data
DIAG(F("Railcom: Loopback test: %s/%d RX FIFO Data"), _I2CAddress.toString(), _UART_CH);
for (int i = 0; i < inlen; i++){
DIAG(F("Railcom: Loopback data [0x%x]: 0x%x"), i, _inbuf[i]);
//DIAG(F("[0x%x]: 0x%x"), i, _inbuf[i]);
}
#endif
}
UART_WriteRegister(REG_MCR, 0x00); // Set REG_MCR back to 0x00
#endif
#ifdef DIAG_I2CRailcom
// Sent some data to check if UART baudrate is set correctly, check with logic analyzer on TX pin
UART_WriteRegister(REG_THR, 9, false);
DIAG(F("I2CRailcom: UART %s/%d Test TX = 0x09"),_I2CAddress.toString(), _UART_CH);
#endif
if (_deviceState==DEVSTATE_INITIALISING) {
DIAG(F("I2CRailcom: UART %d init complete"),_UART_CH);
}
// HK: final FIFO reset
UART_WriteRegister(REG_FCR, 0x07,false); // Reset FIFO, clear RX & TX FIFO (write only)
}
void I2CRailcom::UART_WriteRegister(uint8_t reg, uint8_t val, bool readback){
_outbuf[0] = (byte)( reg << 3 | _UART_CH << 1);
_outbuf[1]=val;
auto status=I2CManager.write(_I2CAddress, _outbuf, (uint8_t)2);
if(status!=I2C_STATUS_OK) {
DIAG(F("I2CRailcom: %s/%d write reg=0x%x,data=0x%x,I2Cstate=%d"),
_I2CAddress.toString(), _UART_CH, reg, val, status);
_deviceState=DEVSTATE_FAILED;
}
if (readback) { // Read it back to cross check
auto readback=UART_ReadRegister(reg);
if (readback!=val) {
DIAG(F("I2CRailcom readback: %s/%d reg:0x%x write=0x%x read=0x%x"),_I2CAddress.toString(),_UART_CH,reg,val,readback);
}
}
}
uint8_t I2CRailcom::UART_ReadRegister(uint8_t reg){
_outbuf[0] = (byte)(reg << 3 | _UART_CH << 1); // _outbuffer[0] has now UART_REG and UART_CH
_inbuf[0]=0;
auto status=I2CManager.read(_I2CAddress, _inbuf, 1, _outbuf, 1);
if (status!=I2C_STATUS_OK) {
DIAG(F("I2CRailcom read: %s/%d read reg=0x%x,I2Cstate=%d"),
_I2CAddress.toString(), _UART_CH, reg, status);
_deviceState=DEVSTATE_FAILED;
}
return _inbuf[0];
}
// SC16IS752 General register set (from the datasheet)
enum : uint8_t {
REG_RHR = 0x00, // FIFO Read
REG_THR = 0x00, // FIFO Write
REG_IER = 0x01, // Interrupt Enable Register R/W
REG_FCR = 0x02, // FIFO Control Register Write
REG_IIR = 0x02, // Interrupt Identification Register Read
REG_LCR = 0x03, // Line Control Register R/W
REG_MCR = 0x04, // Modem Control Register R/W
REG_LSR = 0x05, // Line Status Register Read
REG_MSR = 0x06, // Modem Status Register Read
REG_SPR = 0x07, // Scratchpad Register R/W
REG_TCR = 0x06, // Transmission Control Register R/W
REG_TLR = 0x07, // Trigger Level Register R/W
REG_TXLV = 0x08, // Transmitter FIFO Level register Read
REG_RXLV = 0x09, // Receiver FIFO Level register Read
REG_IODIR = 0x0A, // Programmable I/O pins Direction register R/W
REG_IOSTATE = 0x0B, // Programmable I/O pins State register R/W
REG_IOINTENA = 0x0C, // I/O Interrupt Enable register R/W
REG_IOCONTROL = 0x0E, // I/O Control register R/W
REG_EFCR = 0x0F, // Extra Features Control Register R/W
};
// SC16IS752 Special register set
enum : uint8_t{
REG_DLL = 0x00, // Division registers R/W
REG_DLH = 0x01, // Division registers R/W
};
// SC16IS752 Enhanced regiter set
enum : uint8_t{
REG_EFR = 0X02, // Enhanced Features Register R/W
REG_XON1 = 0x04, // R/W
REG_XON2 = 0x05, // R/W
REG_XOFF1 = 0x06, // R/W
REG_XOFF2 = 0x07, // R/W
};

View File

@ -1,145 +0,0 @@
/*
* © 2024, Henk Kruisbrink & Chris Harlow. All rights reserved.
* © 2023, Neil McKechnie. All rights reserved.
*
* This file is part of DCC++EX API
*
* This is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* 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/>.
*/
/*
*
* Dec 2023, Added NXP SC16IS752 I2C Dual UART
* The SC16IS752 has 64 bytes TX & RX FIFO buffer
* First version without interrupts from I2C UART and only RX/TX are used, interrupts may not be
* needed as the RX Fifo holds the reply
*
* Jan 2024, Issue with using both UARTs simultaniously, the secod uart seems to work but the first transmit
* corrupt data. This need more analysis and experimenatation.
* Will push this driver to the dev branch with the uart fixed to 0
* Both SC16IS750 (single uart) and SC16IS752 (dual uart, but only uart 0 is enable)
*
* myHall.cpp configuration syntax:
*
* I2CRailcom::create(1st vPin, vPins, I2C address);
*
* myAutomation configuration
* HAL(I2CRailcom, 1st vPin, vPins, I2C address)
* Parameters:
* 1st vPin : First virtual pin that EX-Rail can control to play a sound, use PLAYSOUND command (alias of ANOUT)
* vPins : Total number of virtual pins allocated (2 vPins are supported, one for each UART)
* 1st vPin for UART 0, 2nd for UART 1
* I2C Address : I2C address of the serial controller, in 0x format
*/
#ifndef IO_I2CRailcom_h
#define IO_I2CRailcom_h
#include "Arduino.h"
#include "Railcom.h"
// Debug and diagnostic defines, enable too many will result in slowing the driver
#define DIAG_I2CRailcom
class I2CRailcom : public IODevice {
private:
// SC16IS752 defines
uint8_t _UART_CH=0x00; // channel 0 or 1 flips each loop if npins>1
byte _inbuf[12];
byte _outbuf[2];
byte cutoutCounter[2];
Railcom * _channelMonitors[2];
public:
// Constructor
I2CRailcom(VPIN firstVpin, int nPins, I2CAddress i2cAddress);
static void create(VPIN firstVpin, int nPins, I2CAddress i2cAddress) ;
void _begin() ;
void _loop(unsigned long currentMicros) override ;
void _display() override ;
private:
// SC16IS752 functions
// Initialise SC16IS752 only for this channel
// First a software reset
// Enable FIFO and clear TX & RX FIFO
// Need to set the following registers
// IOCONTROL set bit 1 and 2 to 0 indicating that they are GPIO
// IODIR set all bit to 1 indicating al are output
// IOSTATE set only bit 0 to 1 for UART 0, or only bit 1 for UART 1 //
// LCR bit 7=0 divisor latch (clock division registers DLH & DLL, they store 16 bit divisor),
// WORD_LEN, STOP_BIT, PARITY_ENA and PARITY_TYPE
// MCR bit 7=0 clock divisor devide-by-1 clock input
// DLH most significant part of divisor
// DLL least significant part of divisor
//
// BAUD_RATE, WORD_LEN, STOP_BIT, PARITY_ENA and PARITY_TYPE have been defined and initialized
//
// Communication parameters 8 bit, No parity, 1 stopbit
static const uint8_t WORD_LEN = 0x03; // Value LCR bit 0,1
static const uint8_t STOP_BIT = 0x00; // Value LCR bit 2
static const uint8_t PARITY_ENA = 0x00; // Value LCR bit 3
static const uint8_t PARITY_TYPE = 0x00; // Value LCR bit 4
static const uint32_t BAUD_RATE = 250000;
static const uint8_t PRESCALER = 0x01; // Value MCR bit 7
static const unsigned long SC16IS752_XTAL_FREQ_RAILCOM = 16000000; // Baud rate for Railcom signal
static const uint16_t _divisor = (SC16IS752_XTAL_FREQ_RAILCOM / PRESCALER) / (BAUD_RATE * 16);
void Init_SC16IS752();
void UART_WriteRegister(uint8_t reg, uint8_t val, bool readback=true);
uint8_t UART_ReadRegister(uint8_t reg);
// SC16IS752 General register set (from the datasheet)
enum : uint8_t {
REG_RHR = 0x00, // FIFO Read
REG_THR = 0x00, // FIFO Write
REG_IER = 0x01, // Interrupt Enable Register R/W
REG_FCR = 0x02, // FIFO Control Register Write
REG_IIR = 0x02, // Interrupt Identification Register Read
REG_LCR = 0x03, // Line Control Register R/W
REG_MCR = 0x04, // Modem Control Register R/W
REG_LSR = 0x05, // Line Status Register Read
REG_MSR = 0x06, // Modem Status Register Read
REG_SPR = 0x07, // Scratchpad Register R/W
REG_TCR = 0x06, // Transmission Control Register R/W
REG_TLR = 0x07, // Trigger Level Register R/W
REG_TXLV = 0x08, // Transmitter FIFO Level register Read
REG_RXLV = 0x09, // Receiver FIFO Level register Read
REG_IODIR = 0x0A, // Programmable I/O pins Direction register R/W
REG_IOSTATE = 0x0B, // Programmable I/O pins State register R/W
REG_IOINTENA = 0x0C, // I/O Interrupt Enable register R/W
REG_IOCONTROL = 0x0E, // I/O Control register R/W
REG_EFCR = 0x0F, // Extra Features Control Register R/W
};
// SC16IS752 Special register set
enum : uint8_t{
REG_DLL = 0x00, // Division registers R/W
REG_DLH = 0x01, // Division registers R/W
};
// SC16IS752 Enhanced regiter set
enum : uint8_t{
REG_EFR = 0X02, // Enhanced Features Register R/W
REG_XON1 = 0x04, // R/W
REG_XON2 = 0x05, // R/W
REG_XOFF1 = 0x06, // R/W
REG_XOFF2 = 0x07, // R/W
};
};
#endif // IO_I2CRailcom_h

View File

@ -22,7 +22,6 @@
#include <Arduino.h>
#include "IODevice.h"
#include "IO_TM1638.h"
#include "DIAG.h"

View File

@ -1,276 +0,0 @@
/*
* SEE ADDITIONAL COPYRIGHT ATTRIBUTION BELOW
* © 2024 Chris Harlow
* All rights reserved.
*
* This file is part of DCC-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/>.
*/
/** Sections of this code (the decode table constants)
* are taken from openmrn
* https://github.com/bakerstu/openmrn/blob/master/src/dcc/RailCom.cxx
* under the following copyright.
*
* Copyright (c) 2014, Balazs Racz
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
*
* - Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
**/
#include "Railcom.h"
#include "defines.h"
#include "FSH.h"
#include "DCC.h"
#include "DIAG.h"
#include "DCCWaveform.h"
/** Table for 8-to-6 decoding of railcom data. This table can be indexed by the
* 8-bit value read from the railcom channel, and the return value will be
* either a 6-bit number, or one of the defined Railcom constrantrs. If the
* value is invalid, the INV constant is returned. */
// These values appear in the railcom_decode table to mean special symbols.
static constexpr uint8_t
// highest valid 6-bit value
MAX_VALID = 0x3F,
/// invalid value (not conforming to the 4bit weighting requirement)
INV = 0xff,
/// Railcom ACK; the decoder received the message ok. NOTE: There are
/// two codepoints that map to this.
ACK = 0xfe,
/// The decoder rejected the packet.
NACK = 0xfd,
/// The decoder is busy; send the packet again. This is typically
/// returned when a POM CV write is still pending; the caller must
/// re-try sending the packet later.
RCBUSY = 0xfc,
/// Reserved for future expansion.
RESVD1 = 0xfb,
/// Reserved for future expansion.
RESVD2 = 0xfa;
const uint8_t HIGHFLASH decode[256] =
// 0|8 1|9 2|a 3|b 4|c 5|d 6|e 7|f
{ INV, INV, INV, INV, INV, INV, INV, INV, // 0
INV, INV, INV, INV, INV, INV, INV, ACK, // 0
INV, INV, INV, INV, INV, INV, INV, 0x33, // 1
INV, INV, INV, 0x34, INV, 0x35, 0x36, INV, // 1
INV, INV, INV, INV, INV, INV, INV, 0x3A, // 2
INV, INV, INV, 0x3B, INV, 0x3C, 0x37, INV, // 2
INV, INV, INV, 0x3F, INV, 0x3D, 0x38, INV, // 3
INV, 0x3E, 0x39, INV, NACK, INV, INV, INV, // 3
INV, INV, INV, INV, INV, INV, INV, 0x24, // 4
INV, INV, INV, 0x23, INV, 0x22, 0x21, INV, // 4
INV, INV, INV, 0x1F, INV, 0x1E, 0x20, INV, // 5
INV, 0x1D, 0x1C, INV, 0x1B, INV, INV, INV, // 5
INV, INV, INV, 0x19, INV, 0x18, 0x1A, INV, // 6
INV, 0x17, 0x16, INV, 0x15, INV, INV, INV, // 6
INV, 0x25, 0x14, INV, 0x13, INV, INV, INV, // 7
0x32, INV, INV, INV, INV, INV, INV, INV, // 7
INV, INV, INV, INV, INV, INV, INV, RESVD2, // 8
INV, INV, INV, 0x0E, INV, 0x0D, 0x0C, INV, // 8
INV, INV, INV, 0x0A, INV, 0x09, 0x0B, INV, // 9
INV, 0x08, 0x07, INV, 0x06, INV, INV, INV, // 9
INV, INV, INV, 0x04, INV, 0x03, 0x05, INV, // a
INV, 0x02, 0x01, INV, 0x00, INV, INV, INV, // a
INV, 0x0F, 0x10, INV, 0x11, INV, INV, INV, // b
0x12, INV, INV, INV, INV, INV, INV, INV, // b
INV, INV, INV, RESVD1, INV, 0x2B, 0x30, INV, // c
INV, 0x2A, 0x2F, INV, 0x31, INV, INV, INV, // c
INV, 0x29, 0x2E, INV, 0x2D, INV, INV, INV, // d
0x2C, INV, INV, INV, INV, INV, INV, INV, // d
INV, RCBUSY, 0x28, INV, 0x27, INV, INV, INV, // e
0x26, INV, INV, INV, INV, INV, INV, INV, // e
ACK, INV, INV, INV, INV, INV, INV, INV, // f
INV, INV, INV, INV, INV, INV, INV, INV, // f
};
/// Packet identifiers from Mobile Decoders.
enum RailcomMobilePacketId
{
RMOB_POM = 0,
RMOB_ADRHIGH = 1,
RMOB_ADRLOW = 2,
RMOB_EXT = 3,
RMOB_DYN = 7,
RMOB_XPOM0 = 8,
RMOB_XPOM1 = 9,
RMOB_XPOM2 = 10,
RMOB_XPOM3 = 11,
RMOB_SUBID = 12,
RMOB_LOGON_ASSIGN_FEEDBACK = 13,
RMOB_LOGON_ENABLE_FEEDBACK = 15,
};
// each railcom block is represented by an instance of this class.
// The blockvpin is the vpin associated with this block for the purposes of
// a HAL driver for the railcom detection and the EXRAIL ONBLOCKENTER/ONBLOCKEXIT
// need to know if there is any detector Railcom detector
// otherwise <r cab cv> would block the async reply feature.
bool Railcom::hasActiveDetectors=false;
Railcom::Railcom(uint16_t blockvpin) {
DIAG(F("Create Railcom block %d"),blockvpin);
haveHigh=false;
haveLow=false;
packetsWithNoData=0;
lastChannel1Loco=0;
vpin=blockvpin;
}
uint16_t Railcom::expectLoco=0;
uint16_t Railcom::expectCV=0;
unsigned long Railcom::expectWait=0;
ACK_CALLBACK Railcom::expectCallback=0;
// Process is called by a raw data collector.
void Railcom::process(uint8_t * inbound, uint8_t length) {
hasActiveDetectors=true;
if (length<2 || (inbound[0]==0 && inbound[1]==0)) {
noData();
return;
}
if (Diag::RAILCOM) {
static const char hexchars[]="0123456789ABCDEF";
if (length>2) {
USB_SERIAL.print(F("<*R "));
for (byte i=0;i<length;i++) {
if (i==2) Serial.write(' ');
USB_SERIAL.write(hexchars[inbound[i]>>4]);
USB_SERIAL.write(hexchars[inbound[i]& 0x0F ]);
}
USB_SERIAL.print(F(" *>\n"));
}
}
if (expectCV && DCCWaveform::getRailcomLastLocoAddress()==expectLoco) {
if (length>=4) {
auto v2=GETHIGHFLASH(decode,inbound[2]);
auto v3=GETHIGHFLASH(decode,inbound[3]);
uint16_t packet=(v2<<6) | (v3 & 0x3f);
// packet is 12 bits TTTTDDDDDDDD
byte type=(packet>>8) & 0x0F;
byte data= packet & 0xFF;
if (type==RMOB_POM) {
// DIAG(F("POM READ loco=%d cv(%d)=%d/0x%x"), expectLoco, expectCV,data,data);
expectCallback(data);
expectCV=0;
}
}
}
if (expectCV && (millis()-expectWait)> POM_READ_TIMEOUT) { // still waiting
expectCallback(-1);
expectCV=0;
}
auto v1=GETHIGHFLASH(decode,inbound[0]);
auto v2=(length>1) ? GETHIGHFLASH(decode,inbound[1]):INV;
uint16_t packet=(v1<<6) | (v2 & 0x3f);
// packet is 12 bits TTTTDDDDDDDD
byte type=(packet>>8) & 0x0F;
byte data= packet & 0xFF;
if (type==RMOB_ADRHIGH) {
holdoverHigh=data;
haveHigh=true;
packetsWithNoData=0;
}
else if (type==RMOB_ADRLOW) {
holdoverLow=data;
haveLow=true;
packetsWithNoData=0;
}
else {
// channel1 is unreadable or not loco address so maybe multiple locos in block
if (length>2 && GETHIGHFLASH(decode,inbound[0])!=INV) {
// it looks like we have channel2 data
auto thisLoco=DCCWaveform::getRailcomLastLocoAddress();
if (Diag::RAILCOM) DIAG(F("c2=%d"),thisLoco);
if (thisLoco==lastChannel1Loco) return;
if (thisLoco) DCC::setLocoInBlock(thisLoco,vpin,false); // this loco is in block, but not exclusive
return;
}
// channel1 no good and no channel2
noData();
return;
}
if (haveHigh && haveLow) {
uint16_t thisLoco=((holdoverHigh<<8)| holdoverLow) & 0x7FFF; // drop top bit
if (thisLoco!=lastChannel1Loco) {
// the exclusive DCC call is quite expensive, we dont want to call it every packet
if (Diag::RAILCOM) DIAG(F("h=%x l=%xc1=%d"),holdoverHigh, holdoverLow,thisLoco);
DCC::setLocoInBlock(thisLoco,vpin,true); // only this loco is in block
lastChannel1Loco=thisLoco;
}
}
}
void Railcom::noData() {
if (packetsWithNoData>MAX_WAIT_FOR_GLITCH) return;
if (packetsWithNoData==MAX_WAIT_FOR_GLITCH) {
// treat as no loco
haveHigh=false;
haveLow=false;
lastChannel1Loco=0;
// Previous locos (if any) is exiting block
DCC::clearBlock(vpin);
}
packetsWithNoData++;
}
// anticipate is used when waiting for a CV read from a railcom loco
void Railcom::anticipate(uint16_t loco, uint16_t cv, ACK_CALLBACK callback) {
if (!hasActiveDetectors) {
// if there are no active railcom detectors, this will
// not be timed out in process()... so deny it now.
callback(-2);
return;
}
expectLoco=loco;
expectCV=cv;
expectWait=millis(); // start of timeout
expectCallback=callback;
};

View File

@ -1,53 +0,0 @@
/*
* © 2024 Chris Harlow
* All rights reserved.
*
* This file is part of DCC-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 Railcom_h
#define Railcom_h
#include "Arduino.h"
typedef void (*ACK_CALLBACK)(int16_t result);
class Railcom {
public:
Railcom(uint16_t vpin);
/* Process returns -1: Call again next packet
0: No loco on track
>0: loco id
*/
void process(uint8_t * inbound,uint8_t length);
static void anticipate(uint16_t loco, uint16_t cv, ACK_CALLBACK callback);
private:
static bool hasActiveDetectors;
static const unsigned long POM_READ_TIMEOUT=500; // as per spec
static uint16_t expectCV,expectLoco;
static unsigned long expectWait;
static ACK_CALLBACK expectCallback;
void noData();
uint16_t vpin;
uint8_t holdoverHigh,holdoverLow;
bool haveHigh,haveLow;
uint8_t packetsWithNoData;
uint16_t lastChannel1Loco;
static const byte MAX_WAIT_FOR_GLITCH=20; // number of dead or empty packets before assuming loco=0
};
#endif

Binary file not shown.

View File

@ -1,75 +0,0 @@
Railcom implementation notes, Chris Harlow Oct 2024
Railcom support is in 3 parts
1. Generation of the DCC waveform with a Railcom cutout.
2. Accessing the railcom feedback from a loco using hardware detectors
3. Utilising the feedback to do something useful.
DCC Waveform Railcom cutout depends on using suitable motor shields (EX8874 primarily) as the standard Arduino shield is not suitable. (Too high resistance during cutout)
The choice of track management also depends on wiring all the MAIN tracks to use the same signal and brake pins. This allows separate track power management but prevents switching a single track from MAIN to PROG or DC...
Some CPUs require very specific choice of brake pins etc to match their internal timer register architecture.
- MEGA.. The default shield setting for an EX8874 is suitable for Railcom on Channel A (MAIN)
- ESP32 .. not yet supported.
- Nucleo ... TBA
Enabling the Railcom Cutout requires a `<C RAILCOM ON>` command. This can be added to myAutomation using `PARSE("<C RAILCOM ON>")`
Code to calculate the cutout position and provide synchronization for the sampling is in `DCCWaveform.cpp` (not ESP32)
and in general a global search for "railcom" will show all code changes that have been made to support this.
Code to actually implement the timing of the cutout is hihjly cpu dependent and can be found in gthe various implementations of `DCCTimer.h`. At this time only `DCCTimerAVR.cpp`has implemented this.
Reading Railcom data:
A new HAL handler (`IO_I2CRailcom.h`)has been added to process input from a 2-block railcom reader (Refer Henk) which operates as a 2 channel UART accessible over I2C. The reader(s) sit between the CS and the track and collect railcom data from locos during the cutout.
After the cutout the HAL driver reads the UARTs over I2C and passes the raw data to the CS logic (`Railcom.cpp`)for analysis.
Each 2-block reader is described in myAutomation like `HAL(I2CRailcom,10000,2,0x48)` which will assign 2 channels on i2c address 0x48 with vpin numbers 10000 and 10001. If you only use the first channel in the reader, just asign one pin instead of two.
(Implementation notes.. potentially other readers are possible with suitable HAL drivers. There are however several touch-points with the code DCC Waveform code which helps the HAL driver to understand when the data is safe to sample, and how to interpret responses when the sender is unknown. )
Making use of Railcom data
Exrail has two additional event handlers which can capture locos entering and exiting blocks. These handlers are started with the loco information already set, so for example:
```
ONBLOCKENTER(10000)
// a loco has entered block 10000
FON(0) // turn the light on
FON(1) // make a lot of noise
SPEED(20) // slow down
DONE
ONBLOCKEXIT(10000)
// a loco has left block 10000
FOFF(0) // turn the light off
FOFF(1) // stop the noise
SPEED(50) // speed up again
DONE
```
Note that the Railcom interpretation code is capable of detecting multiple locos in the same block at the same time and will create separate exrail tasks for each one.
There is however one minor loophole in the block exit logic...
If THREE or more locos are in the same block and ONE of them leaves, then ONBLOCKEXIT will not fire until
EITHER - The leaving loco enters another railcom block
OR - only ONE loco remains in the block just left.
To further support block management in railcom, two additional serial commands are available
`<K block loco >` to simulate a loco entering a block, and trigger any ONBLOCKENTER
`<k block loco >` to simulate a loco leaving a block, and trigger and ONBLOCKEXIT
Reading CV values on MAIN.
Railcom allows for the facility to read loco cv values while on the main track. This is considerably faster than PROG track access but depends on the loco being in a Railcom monitored block.
To read from prog Track we use `<R cv>` response is `<r value>`
To read from main track use `<r loco cv>`
response is `<r loco cv value>`
Additional EXRAIL features in Railcom Branch:
- ESTAOPALL stops all locos immediately
- XPOM(cab,cv,value) POM write cv to sepcific loco
(POM(cv,value) already writes cv to current loco)

View File

@ -1,29 +0,0 @@
New Momentum feature notes:
The command station can apply momentum to throttle movements in the same way that a standards compliant DCC decoder can be set to do. This momentum can be defaulted system wide and overridden on individual locos. It does not use or alter the loco CV values and so it also works when driving DC locos.
The momentum is applied regardless of the throttle type used (or even EXRAIL).
Momentum is specified in mS / throttle_step.
There is a new command `<m cabid accelerating [brake]>`
where the brake value defaults to the accelerating value.
For example:
`<m 3 0>` sets loco 3 to no momentum.
`<m 3 21>` sets loco 3 to 21 mS/step.
`<m 3 21 42>` sets loco 3 to 21 mS/step accelerating and 42 mS/step when decelerating.
`<m 0 21>` sets the default momentum to 21mS/Step for all current and future locos that have not been specifically set.
`<m 3 -1>` sets loco 3 to track the default momentum value.
EXRAIL
A new macro `MOMENTUM(accel [, decel])` sets the momentum value of the current tasks loco ot the global default if loco=0.
Note: Setting Momentum 7,14,21 etc is similar in effect to setting a decoder CV03/CV04 to 1,2,3.
As an additional option, the momentum calculation is based on the
difference in throttle setting and actual speed. For example, the time taken to reach speed 50 from a standing start would be less if the throttle were set to speed 100, thus increasing the acceleration.
`<m LINEAR>` - acceleration is uniform up to selected throttle speed.
`<m POWER>` - acceleration depends on difference between loco speed and selected throttle speed.

View File

@ -1,41 +0,0 @@
<html>
<!-- Minimalist test page for the DCCEX websocket API.-->
<head>
<script>
let socket = new WebSocket("ws://192.168.1.242:2560","DCCEX");
// send message from the form
var sender = function() {
var msg=document.getElementById('message').value;
socket.send(msg);
}
// message received - show the message in div#messages
socket.onmessage = function(event) {
let message = event.data;
let messageElem = document.createElement('div');
messageElem.textContent = message;
document.getElementById('messages').prepend(messageElem);
}
socket.onerror = function(event) {
let message = event.data;
let messageElem = document.createElement('div');
messageElem.textContent = message;
document.getElementById('messages').prepend(messageElem);
}
</script>
</head>
<body>
This is a minimalist test page for the DCCEX websocket API.
It demonstrates the Websocket connection and how to send
or receive websocket traffic.
The connection string must be edited to address your command station
correctly.<p>
<!-- message form -->
<input type="text" id="message">
<input type="button" value="Send" onclick="sender();">
<!-- div with messages -->
<div id="messages"></div>
</body>
</html>

View File

@ -1,101 +0,0 @@
/*
* © 2024 Harald Barth
* 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/>.
*/
//
// Rewrite of the STM32lwipopts.h file from STM
// To be copied into where lwipopts_default.h resides
// typically into STM32Ethernet/src/STM32lwipopts.h
// or STM32Ethernet\src\STM32lwipopts.h
// search for `lwipopts_default.h` and copy this file into the
// same directory but name it STM32lwipopts.h
//
#ifndef __STM32LWIPOPTS_H__
#define __STM32LWIPOPTS_H__
// include this here and then override things we do differnet
#include "lwipopts_default.h"
// we can not include our "defines.h" here
// so we need to duplicate that define
#define MAX_NUM_TCP_CLIENTS_HERE 9
#ifdef MAX_NUM_TCP_CLIENTS
#if MAX_NUM_TCP_CLIENTS != MAX_NUM_TCP_CLIENTS_HERE
#error MAX_NUM_TCP_CLIENTS and MAX_NUM_TCP_CLIENTS_HERE must be same
#endif
#else
#define MAX_NUM_TCP_CLIENTS MAX_NUM_TCP_CLIENTS_HERE
#endif
// increase ARP cache
#undef MEMP_NUM_APR_QUEUE
#define MEMP_NUM_ARP_QUEUE MAX_NUM_TCP_CLIENTS+3 // one for each client (all on different HW) and a few extra
// Example for debug
//#define LWIP_DEBUG 1
//#define TCP_DEBUG LWIP_DBG_ON
// NOT STRICT NECESSARY ANY MORE BUT CAN BE USED TO SAVE RAM
#undef MEM_LIBC_MALLOC
#define MEM_LIBC_MALLOC 1 // use the same malloc as for everything else
#undef MEMP_MEM_MALLOC
#define MEMP_MEM_MALLOC 1 // uses malloc which means no pools which means slower but not mean 32KB up front
#undef MEMP_NUM_TCP_PCB
#define MEMP_NUM_TCP_PCB MAX_NUM_TCP_CLIENTS+1 // one extra so we can reject number N+1 from our code
#define MEMP_NUM_TCP_PCB_LISTEN 6
#undef MEMP_NUM_TCP_SEG
#define MEMP_NUM_TCP_SEG MAX_NUM_TCP_CLIENTS
#undef MEMP_NUM_SYS_TIMEOUT
#define MEMP_NUM_SYS_TIMEOUT MAX_NUM_TCP_CLIENTS+2
#undef PBUF_POOL_SIZE
#define PBUF_POOL_SIZE MAX_NUM_TCP_CLIENTS
#undef LWIO_ICMP
#define LWIP_ICMP 1
#undef LWIP_RAW
#define LWIP_RAW 1 /* PING changed to 1 */
#undef DEFAULT_RAW_RECVMBOX_SIZE
#define DEFAULT_RAW_RECVMBOX_SIZE 3 /* for ICMP PING */
#undef LWIP_DHCP
#define LWIP_DHCP 1
#undef LWIP_UDP
#define LWIP_UDP 1
/*
The STM32F4x7 allows computing and verifying the IP, UDP, TCP and ICMP checksums by hardware:
- To use this feature let the following define uncommented.
- To disable it and process by CPU comment the the checksum.
*/
#if CHECKSUM_GEN_TCP == 1
#error On STM32 TCP checksum should be in HW
#endif
#undef LWIP_IGMP
#define LWIP_IGMP 1
//#define SO_REUSE 1
//#define SO_REUSE_RXTOALL 1
#endif /* __STM32LWIPOPTS_H__ */

View File

@ -126,29 +126,33 @@ void SerialManager::loop2() {
buffer[0] = '\0';
}
} else { // if (inCommandPayload)
if (bufferLength < (COMMAND_BUFFER_SIZE-1))
buffer[bufferLength++] = ch;
if (inCommandPayload > PAYLOAD_NORMAL) {
if (inCommandPayload > 32 + 2) { // String way too long
ch = '>'; // we end this nonsense
inCommandPayload = PAYLOAD_NORMAL;
DIAG(F("Parse error: Unbalanced string"));
// fall through to ending parsing below
} else if (ch == '"') { // String end
inCommandPayload = PAYLOAD_NORMAL;
continue; // do not fall through
} else
inCommandPayload++;
}
if (inCommandPayload == PAYLOAD_NORMAL) {
if (ch == '>') {
buffer[bufferLength] = '\0';
DCCEXParser::parse(serial, buffer, NULL);
inCommandPayload = PAYLOAD_FALSE;
break;
} else if (ch == '"') {
inCommandPayload = PAYLOAD_STRING;
}
if (bufferLength < (COMMAND_BUFFER_SIZE-1)) {
buffer[bufferLength++] = ch; // advance bufferLength
if (inCommandPayload > PAYLOAD_NORMAL) {
if (inCommandPayload > 32 + 2) { // String way too long
ch = '>'; // we end this nonsense
inCommandPayload = PAYLOAD_NORMAL;
DIAG(F("Parse error: Unbalanced string"));
// fall through to ending parsing below
} else if (ch == '"') { // String end
inCommandPayload = PAYLOAD_NORMAL;
continue; // do not fall through
} else
inCommandPayload++;
}
if (inCommandPayload == PAYLOAD_NORMAL) {
if (ch == '>') {
buffer[bufferLength] = '\0'; // This \0 is after the '>'
DCCEXParser::parse(serial, buffer, NULL); // buffer parsed with trailing '>'
inCommandPayload = PAYLOAD_FALSE;
break;
} else if (ch == '"') {
inCommandPayload = PAYLOAD_STRING;
}
}
} else {
DIAG(F("Parse error: input buffer overflow"));
inCommandPayload = PAYLOAD_FALSE;
}
}
}

View File

@ -1,5 +1,5 @@
/*
* © 2020=2025, Chris Harlow. All rights reserved.
* © 2020, Chris Harlow. All rights reserved.
*
* This file is part of Asbelos DCC API
*
@ -27,9 +27,6 @@ bool Diag::WIFI=false;
bool Diag::WITHROTTLE=false;
bool Diag::ETHERNET=false;
bool Diag::LCN=false;
bool Diag::RAILCOM=false;
bool Diag::WEBSOCKET=false;
void StringFormatter::diag( const FSH* input...) {

View File

@ -1,5 +1,5 @@
/*
* © 2020-2025, Chris Harlow. All rights reserved.
* © 2020, Chris Harlow. All rights reserved.
*
* This file is part of Asbelos DCC API
*
@ -30,8 +30,6 @@ class Diag {
static bool WITHROTTLE;
static bool ETHERNET;
static bool LCN;
static bool RAILCOM;
static bool WEBSOCKET;
};

View File

@ -1,5 +1,5 @@
/*
* © 2022-2025 Chris Harlow
* © 2022 Chris Harlow
* © 2022-2024 Harald Barth
* © 2023-2024 Paul M. Antoine
* © 2024 Herb Morton
@ -332,8 +332,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
canDo &= track[t]->trackPWM;
}
}
if (canDo) DIAG(F("HA mode"));
else {
if (!canDo) {
// if we discover that HA mode was globally impossible
// we must adjust the trackPWM capabilities
FOR_EACH_TRACK(t) {
@ -342,7 +341,6 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
}
DCCTimer::clearPWM(); // has to be AFTER trackPWM changes because if trackPWM==true this is undone for that track
}
DCCWaveform::setRailcomPossible(canDo);
#else
// For ESP32 we just reinitialize the DCC Waveform
DCCWaveform::begin();
@ -381,7 +379,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
}
void TrackManager::applyDCSpeed(byte t) {
track[t]->setDCSignal(DCC::getLocoSpeedByte(trackDCAddr[t]),
track[t]->setDCSignal(DCC::getThrottleSpeedByte(trackDCAddr[t]),
DCC::getThrottleFrequency(trackDCAddr[t]));
}
@ -670,7 +668,8 @@ void TrackManager::setJoin(bool joined) {
if (track[t]->getMode() & TRACK_MODE_PROG) { // find PROG track
tempProgTrack = t; // remember PROG track
setTrackMode(t, TRACK_MODE_MAIN);
track[t]->setPower(POWERMODE::ON); // if joined, always on
// setPower() of the track called after
// seperately after setJoin() instead
break; // there is only one prog track, done
}
}
@ -682,8 +681,6 @@ void TrackManager::setJoin(bool joined) {
setTrackMode(tempProgTrack, TRACK_MODE_PROG); // set track mode back to prog
track[tempProgTrack]->setPower(tPTmode); // set power status as it was before
tempProgTrack = MAX_TRACKS+1;
} else {
DIAG(F("Unjoin but no remembered prog track"));
}
}
#endif

View File

@ -1,211 +0,0 @@
/*
* © 2023 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/>.
*/
/**************************************************
HOW IT WORKS
1) Refer to https://developer.mozilla.org/en-US/docs/Web/API/WebSockets_API/Writing_WebSocket_servers
2) When a new client sends in a socket stream, the
CommandDistributor pass it to this code
checkConnectionString() to check for an HTTP
protocol GET requesting a change to websocket protocol.
[Note that the WifiInboundHandler has a shortcut to detecting this so that
it does not need to use up 500+ bytes of RAM just to get at the one parameter that
actually means something.]
If that is found, the relevant answer is generated and queued and
the CommandDistributor marks this client as a websocket client awaiting connection.
Once the outbound handshake has completed, the CommandDistributor promotes the client
from awaiting connection to connected websocket so that all
future traffic for this client is handled with websocket protocol.
3) When an input is received from a client marked as websocket,
CommandDistributor calls unmask() to strip off the websocket header and
un-mask the input bytes. The command distributor will flag the
clientid in the ringstream so that anyone transmitting this
output will know to handle it differently.
4) when the Wifi/Ethernet handler needs to transmit the result from the
output ring, it recognises the websockets flag and adds the websocket
header to the output dynamically.
*************************************************************/
#include <Arduino.h>
#include "FSH.h"
#include "RingStream.h"
#include "libsha1.h"
#include "Websockets.h"
#include "DIAG.h"
#ifdef ARDUINO_ARCH_ESP32
// ESP32 runtime or definitions has strlcat_P missing
#define strlcat_P strlcat
#endif
static const char b64_table[] = {
'A', 'B', 'C', 'D', 'E', 'F', 'G', 'H',
'I', 'J', 'K', 'L', 'M', 'N', 'O', 'P',
'Q', 'R', 'S', 'T', 'U', 'V', 'W', 'X',
'Y', 'Z', 'a', 'b', 'c', 'd', 'e', 'f',
'g', 'h', 'i', 'j', 'k', 'l', 'm', 'n',
'o', 'p', 'q', 'r', 's', 't', 'u', 'v',
'w', 'x', 'y', 'z', '0', '1', '2', '3',
'4', '5', '6', '7', '8', '9', '+', '/'
};
bool Websockets::checkConnectionString(byte clientId,byte * cmd, RingStream * outbound ) {
// returns true if this input is a websocket connect
if (Diag::WEBSOCKET) DIAG(F("Websock check connection"));
/* Heuristic suppose this is a websocket GET
typically looking like this:
GET / HTTP/1.1
Host: 192.168.1.242:2560
Connection: Upgrade
Pragma: no-cache
Cache-Control: no-cache
User-Agent: Mozilla/5.0 (Windows NT 10.0; Win64; x64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/119.0.0.0 Safari/537.36 Edg/119.0.0.0
Upgrade: websocket
Origin: null
Sec-WebSocket-Version: 13
Accept-Encoding: gzip, deflate
Accept-Language: en-US,en;q=0.9
Sec-WebSocket-Key: SpRkQKPPNZcO62pYf1X6Yg==
Sec-WebSocket-Extensions: permessage-deflate; client_max_window_bits
*/
// check contents to find Sec-WebSocket-Key: and get key up to \n
auto keyPos=strstr_P((char*)cmd,(char*)F("Sec-WebSocket-Key: "));
if (!keyPos) return false;
keyPos+=19; // length of Sec-Websocket-Key:
auto endkeypos=strstr(keyPos,"\r");
if (!endkeypos) return false;
*endkeypos=0;
if (Diag::WEBSOCKET) DIAG(F("Websock key=\"%s\""),keyPos);
// generate the reply key
uint8_t sha1HashBin[21] = { 0 }; // 21 to make it base64 div 3
char replyKey[100];
strlcpy(replyKey,keyPos, sizeof(replyKey));
strlcat_P(replyKey,(char*)F("258EAFA5-E914-47DA-95CA-C5AB0DC85B11"), sizeof(replyKey));
if (Diag::WEBSOCKET) DIAG(F("Websock replykey=%s"),replyKey);
SHA1_CTX ctx;
SHA1Init(&ctx);
SHA1Update(&ctx, (unsigned char *)replyKey, strlen(replyKey));
SHA1Final(sha1HashBin, &ctx);
// generate the response and embed the base64 encode
// of the key
outbound->mark(clientId);
outbound->print(F("HTTP/1.1 101 Switching Protocols\r\n"
"Server: DCCEX-WebSocketsServer\r\n"
"Upgrade: websocket\r\n"
"Connection: Upgrade\r\n"
"Origin: null\r\n"
"Sec-WebSocket-Version: 13\r\n"
"Sec-WebSocket-Protocol: DCCEX\r\n"
"Sec-WebSocket-Accept: "));
// encode and emit the reply key as base 64
auto * tmp=sha1HashBin;
for (int i=0;i<7;i++) {
outbound->print(b64_table[(tmp[0] & 0xfc) >> 2]);
outbound->print(b64_table[((tmp[0] & 0x03) << 4) + ((tmp[1] & 0xf0) >> 4)]);
outbound->print(b64_table[((tmp[1] & 0x0f) << 2) + ((tmp[2] & 0xc0) >> 6)]);
if (i<6) outbound->print(b64_table[tmp[2] & 0x3f]);
tmp+=3;
}
outbound->print(F("=\r\n\r\n")); // because we have padded 1 byte
outbound->commit();
return true;
}
byte * Websockets::unmask(byte clientId,RingStream *ring, byte * buffer) {
// buffer should have a websocket header
//byte opcode=buffer[0] & 0x0f;
if (Diag::WEBSOCKET) DIAG(F("Websock in: %x %x %x %x %x %x %x"),
buffer[0],buffer[1],buffer[2],buffer[3],
buffer[4],buffer[5],buffer[6]);
byte opcode=buffer[0];
bool maskbit=buffer[1]&0x80;
int16_t payloadLength=buffer[1]&0x7f;
byte * mask;
if (payloadLength<126) {
mask=buffer+2;
}
else {
payloadLength=(buffer[3]<<8)|(buffer[2]);
mask=buffer+4;
}
if (Diag::WEBSOCKET) DIAG(F("Websock op=%x mb=%b pl=%d m=%x %x %x %x"), opcode, maskbit, payloadLength,
mask[0],mask[1],mask[2], mask[3]);
if (opcode==0x89) { // ping
DIAG(F("Websock ping"));
buffer[0]=0x8a; // pong.. and send it back
ring->mark(clientId &0x7f); // dont readjust
ring->print((char *)buffer);
ring->commit();
return nullptr;
}
if (opcode!=0x81) {
DIAG(F("Websock unknown opcode 0x%x"),opcode);
return nullptr;
}
byte * payload=mask+4;
for (int i=0;i<payloadLength;i++) {
payload[i]^=mask[i%4];
}
if (Diag::WEBSOCKET) DIAG(F("Websoc payload=%s"),payload);
return payload; // payload will be parsed as normal
}
int16_t Websockets::getOutboundHeaderSize(uint16_t dataLength) {
return (dataLength>=126)? 4:2;
}
int Websockets::fillOutboundHeader(uint16_t dataLength, byte * buffer) {
// text opcode, flag(126= use 2 length bytes, no mask bit) , length
buffer[0]=0x81;
if (dataLength<126) {
buffer[1]=(byte)dataLength;
return 2;
}
buffer[1]=126;
buffer[2]=(byte)(dataLength & 0xFF);
buffer[3]= (byte)(dataLength>>8);
return 4;
}
void Websockets::writeOutboundHeader(Print * stream,uint16_t dataLength) {
byte prefix[4];
int headerlen=fillOutboundHeader(dataLength,prefix);
stream->write(prefix,sizeof(headerlen));
}

View File

@ -1,34 +0,0 @@
/*
* © 2023 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 Websockets_h
#define Websockets_h
#include <Arduino.h>
#include "RingStream.h"
class Websockets {
public:
static bool checkConnectionString(byte clientId,byte * cmd, RingStream * outbound );
static byte * unmask(byte clientId,RingStream *ring, byte * buffer);
static int16_t getOutboundHeaderSize(uint16_t dataLength);
static int fillOutboundHeader(uint16_t dataLength, byte * buffer);
static void writeOutboundHeader(Print * stream,uint16_t dataLength);
static const byte WEBSOCK_CLIENT_MARKER=0x80;
};
#endif

View File

@ -500,9 +500,9 @@ void WiThrottle::getLocoCallback(int16_t locoid) {
char addcmd[20]={'M',stashThrottleChar,'+', addrchar};
itoa(locoid,addcmd+4,10);
stashInstance->multithrottle(stashStream, (byte *)addcmd);
TrackManager::setJoin(true); // <1 JOIN> so we can drive loco away
TrackManager::setMainPower(POWERMODE::ON);
TrackManager::setProgPower(POWERMODE::ON);
TrackManager::setJoin(true); // <1 JOIN> so we can drive loco away
DIAG(F("LocoCallback commit success"));
stashStream->commit();
}

View File

@ -2,8 +2,6 @@
© 2023 Paul M. Antoine
© 2021 Harald Barth
© 2023 Nathan Kellenicki
© 2025 Chris Harlow
This file is part of CommandStation-EX
@ -32,7 +30,6 @@
#include "CommandDistributor.h"
#include "WiThrottle.h"
#include "DCC.h"
#include "Websockets.h"
/*
#include "soc/rtc_wdt.h"
#include "esp_task_wdt.h"
@ -381,8 +378,6 @@ void WifiESP::loop() {
// something to write out?
clientId=outboundRing->read();
bool useWebsocket=clientId & Websockets::WEBSOCK_CLIENT_MARKER;
clientId &= ~ Websockets::WEBSOCK_CLIENT_MARKER;
if (clientId >= 0) {
// We have data to send in outboundRing
// and we have a valid clientId.
@ -390,28 +385,25 @@ void WifiESP::loop() {
// and then look if it can be sent because
// we can not leave it in the ring for ever
int count=outboundRing->count();
auto wsHeaderLen=useWebsocket? Websockets::getOutboundHeaderSize(count) : 0;
{
byte buffer[wsHeaderLen + count + 1]; // one extra for '\0'
if (useWebsocket) Websockets::fillOutboundHeader(count, buffer);
for (int i = 0; i < count; i++) {
int c = outboundRing->read();
if (!c) {
DIAG(F("Ringread fail at %d"), i);
break;
}
// websocket implementations at browser end can barf at \n
if (useWebsocket && (c == '\n')) c = '\r';
buffer[i + wsHeaderLen] = (char)c;
}
// buffer filled, end with '\0' so we can use it as C string
buffer[wsHeaderLen+count]='\0';
char buffer[count+1]; // one extra for '\0'
for(int i=0;i<count;i++) {
int c = outboundRing->read();
if (c >= 0) // Panic check, should never be false
buffer[i] = (char)c;
else {
DIAG(F("Ringread fail at %d"),i);
break;
}
}
// buffer filled, end with '\0' so we can use it as C string
buffer[count]='\0';
if((unsigned int)clientId <= clients.size() && clients[clientId].active(clientId)) {
if (Diag::WIFI)
DIAG(F("SEND%S %d:%s"), useWebsocket?F("ws"):F(""),clientId, buffer+wsHeaderLen);
clients[clientId].wifi.write(buffer,count+wsHeaderLen);
if (Diag::CMD || Diag::WITHROTTLE)
DIAG(F("SEND %d:%s"), clientId, buffer);
clients[clientId].wifi.write(buffer,count);
} else {
DIAG(F("Unsent(%d): %s"), clientId, buffer+wsHeaderLen);
DIAG(F("Unsent(%d): %s"), clientId, buffer);
}
}
}

View File

@ -1,7 +1,7 @@
/*
* © 2021 Fred Decker
* © 2021 Fred Decker
* © 2020-2025 Chris Harlow
* © 2020-2021 Chris Harlow
* © 2020, Chris Harlow. All rights reserved.
* © 2020, Harald Barth.
*
@ -26,7 +26,6 @@
#include "RingStream.h"
#include "CommandDistributor.h"
#include "DIAG.h"
#include "Websockets.h"
WifiInboundHandler * WifiInboundHandler::singleton;
@ -68,13 +67,8 @@ void WifiInboundHandler::loop1() {
if (pendingCipsend && millis()-lastCIPSEND > CIPSENDgap) {
// add allowances for websockets
bool websocket=clientPendingCIPSEND & Websockets::WEBSOCK_CLIENT_MARKER;
byte realClient=clientPendingCIPSEND & ~Websockets::WEBSOCK_CLIENT_MARKER;
int16_t realSize=currentReplySize;
if (websocket) realSize+=Websockets::getOutboundHeaderSize(currentReplySize);
if (Diag::WIFI) DIAG( F("WiFi: [[CIPSEND=%d,%d]]"), realClient, realSize);
StringFormatter::send(wifiStream, F("AT+CIPSEND=%d,%d\r\n"), realClient,realSize);
if (Diag::WIFI) DIAG( F("WiFi: [[CIPSEND=%d,%d]]"), clientPendingCIPSEND, currentReplySize);
StringFormatter::send(wifiStream, F("AT+CIPSEND=%d,%d\r\n"), clientPendingCIPSEND, currentReplySize);
pendingCipsend=false;
return;
}
@ -86,9 +80,7 @@ void WifiInboundHandler::loop1() {
int count=inboundRing->count();
if (Diag::WIFI) DIAG(F("Wifi EXEC: %d %d:"),clientId,count);
byte cmd[count+1];
// Copy raw bytes to avoid websocket masked data being
// confused with a ram-saving flash insert marker.
for (int i=0;i<count;i++) cmd[i]=inboundRing->readRawByte();
for (int i=0;i<count;i++) cmd[i]=inboundRing->read();
cmd[count]=0;
if (Diag::WIFI) DIAG(F("%e"),cmd);
@ -102,9 +94,6 @@ void WifiInboundHandler::loop1() {
// This is a Finite State Automation (FSA) handling the inbound bytes from an ES AT command processor
WifiInboundHandler::INBOUND_STATE WifiInboundHandler::loop2() {
const char WebSocketKeyName[]="Sec-WebSocket-Key: ";
static byte prescanPoint=0;
while (wifiStream->available()) {
int ch = wifiStream->read();
@ -123,12 +112,9 @@ WifiInboundHandler::INBOUND_STATE WifiInboundHandler::loop2() {
}
if (ch=='>') {
bool websocket=clientPendingCIPSEND & Websockets::WEBSOCK_CLIENT_MARKER;
if (Diag::WIFI) DIAG(F("[XMIT %d ws=%b]"),currentReplySize,websocket);
if (websocket) Websockets::writeOutboundHeader(wifiStream,currentReplySize);
if (Diag::WIFI) DIAG(F("[XMIT %d]"),currentReplySize);
for (int i=0;i<currentReplySize;i++) {
int cout=outboundRing->read();
if (websocket && (cout=='\n')) cout='\r';
wifiStream->write(cout);
if (Diag::WIFI) StringFormatter::printEscape(cout); // DIAG in disguise
}
@ -209,19 +195,14 @@ WifiInboundHandler::INBOUND_STATE WifiInboundHandler::loop2() {
break;
}
if (Diag::WIFI) DIAG(F("Wifi inbound data(%d:%d):"),runningClientId,dataLength);
// we normally dont read >100 bytes
// so assume its an HTTP GET or similar
if (dataLength<100 && inboundRing->freeSpace()<=(dataLength+1)) {
if (inboundRing->freeSpace()<=(dataLength+1)) {
// This input would overflow the inbound ring, ignore it
loopState=IPD_IGNORE_DATA;
if (Diag::WIFI) DIAG(F("Wifi OVERFLOW IGNORING:"));
break;
}
inboundRing->mark(runningClientId);
prescanPoint=0;
loopState=(dataLength>100)? IPD_PRESCAN: IPD_DATA;
loopState=IPD_DATA;
break;
}
dataLength = dataLength * 10 + (ch - '0');
@ -236,38 +217,6 @@ WifiInboundHandler::INBOUND_STATE WifiInboundHandler::loop2() {
}
break;
case IPD_PRESCAN: // prescan reading data
dataLength--;
if (dataLength == 0) {
// Nothing found, this input is lost
DIAG(F("Wifi prescan for websock not found"));
inboundRing->commit();
loopState = ANYTHING;
}
if (ch!=WebSocketKeyName[prescanPoint]) {
prescanPoint=0;
break;
}
// matched the next char of the key
prescanPoint++;
if (WebSocketKeyName[prescanPoint]==0) {
if (Diag::WEBSOCKET) DIAG(F("Wifi prescan found"));
// prescan has detected full key
inboundRing->print(WebSocketKeyName);
loopState=IPD_POSTSCAN; // continmue as normal
}
break;
case IPD_POSTSCAN: // reading data
inboundRing->write(ch);
dataLength--;
if (ch=='\n') {
inboundRing->commit();
loopState = IPD_IGNORE_DATA;
}
break;
case IPD_IGNORE_DATA: // ignoring data that would not fit in inbound ring
dataLength--;
if (dataLength == 0) loopState = ANYTHING;

View File

@ -2,7 +2,7 @@
* © 2021 Harald Barth
* © 2021 Fred Decker
* (c) 2021 Fred Decker. All rights reserved.
* (c) 2020-2025 Chris Harlow. All rights reserved.
* (c) 2020 Chris Harlow. All rights reserved.
*
* This file is part of CommandStation-EX
*
@ -55,8 +55,7 @@ class WifiInboundHandler {
IPD6_LENGTH, // got +IPD,c, reading length
IPD_DATA, // got +IPD,c,ll,: collecting data
IPD_IGNORE_DATA, // got +IPD,c,ll,: ignoring the data that won't fit inblound Ring
IPD_PRESCAN, // prescanning data for websocket keys
IPD_POSTSCAN, // copyimg data for websocket keys
GOT_CLIENT_ID, // clientid prefix to CONNECTED / CLOSED
GOT_CLIENT_ID2 // clientid prefix to CONNECTED / CLOSED
};
@ -68,7 +67,7 @@ class WifiInboundHandler {
void purgeCurrentCIPSEND();
Stream * wifiStream;
static const int INBOUND_RING = 128;
static const int INBOUND_RING = 512;
static const int OUTBOUND_RING = sizeof(void*)==2?2048:8192;
static const int CIPSENDgap=100; // millis() between retries of cipsend.

View File

@ -137,16 +137,6 @@ The configuration file for DCC-EX Command Station
//
//#define ENABLE_ETHERNET true
/////////////////////////////////////////////////////////////////////////////////////
//
// MAX_NUM_TCP_CLIENTS: If you on STM32 Ethernet (and only there) want more than
// 9 (*) TCP clients, change this number to for example 20 here **AND** in
// STM32lwiopts.h and follow the instructions in STM32lwiopts.h
//
// (*) It would be 10 if there would not be a bug in LwIP by STM32duino.
//
//#define MAX_NUM_TCP_CLIENTS 20
/////////////////////////////////////////////////////////////////////////////////////
//

View File

@ -239,25 +239,4 @@
#endif
#endif
#if defined(ARDUINO_ARCH_STM32)
// The LwIP library for the STM32 wired ethernet has by default 10 TCP
// clients defined but because of a bug in the library #11 is not
// rejected but kicks out any old connection. By restricting our limit
// to 9 the #10 will be rejected by our code so that the number can
// never get to 11 which would kick an existing connection.
// If you want to change this value, do that in
// config.h AND in STM32lwipopts.h.
#ifndef MAX_NUM_TCP_CLIENTS
#define MAX_NUM_TCP_CLIENTS 9
#endif
#else
#if defined(ARDUINO_ARCH_ESP32)
// Espressif LWIP stack
#define MAX_NUM_TCP_CLIENTS 10
#else
// Wifi shields etc
#define MAX_NUM_TCP_CLIENTS 8
#endif
#endif
#endif //DEFINES_H

View File

@ -1,206 +0,0 @@
// For DCC-EX: This file downloaded from:
// https://github.com/Links2004/arduinoWebSockets
// All due credit to Steve Reid
/* from valgrind tests */
/* ================ sha1.c ================ */
/*
SHA-1 in C
By Steve Reid <steve@edmweb.com>
100% Public Domain
Test Vectors (from FIPS PUB 180-1)
"abc"
A9993E36 4706816A BA3E2571 7850C26C 9CD0D89D
"abcdbcdecdefdefgefghfghighijhijkijkljklmklmnlmnomnopnopq"
84983E44 1C3BD26E BAAE4AA1 F95129E5 E54670F1
A million repetitions of "a"
34AA973C D4C4DAA4 F61EEB2B DBAD2731 6534016F
*/
/* #define LITTLE_ENDIAN * This should be #define'd already, if true. */
/* #define SHA1HANDSOFF * Copies data before messing with it. */
// DCC-EX removed #if !defined(ESP8266) && !defined(ESP32)
#define SHA1HANDSOFF
#include <stdio.h>
#include <string.h>
#include <stdint.h>
#include "libsha1.h"
#define rol(value, bits) (((value) << (bits)) | ((value) >> (32 - (bits))))
/* blk0() and blk() perform the initial expand. */
/* I got the idea of expanding during the round function from SSLeay */
#if BYTE_ORDER == LITTLE_ENDIAN
#define blk0(i) (block->l[i] = (rol(block->l[i],24)&0xFF00FF00) \
|(rol(block->l[i],8)&0x00FF00FF))
#elif BYTE_ORDER == BIG_ENDIAN
#define blk0(i) block->l[i]
#else
#error "Endianness not defined!"
#endif
#define blk(i) (block->l[i&15] = rol(block->l[(i+13)&15]^block->l[(i+8)&15] \
^block->l[(i+2)&15]^block->l[i&15],1))
/* (R0+R1), R2, R3, R4 are the different operations used in SHA1 */
#define R0(v,w,x,y,z,i) z+=((w&(x^y))^y)+blk0(i)+0x5A827999+rol(v,5);w=rol(w,30);
#define R1(v,w,x,y,z,i) z+=((w&(x^y))^y)+blk(i)+0x5A827999+rol(v,5);w=rol(w,30);
#define R2(v,w,x,y,z,i) z+=(w^x^y)+blk(i)+0x6ED9EBA1+rol(v,5);w=rol(w,30);
#define R3(v,w,x,y,z,i) z+=(((w|x)&y)|(w&x))+blk(i)+0x8F1BBCDC+rol(v,5);w=rol(w,30);
#define R4(v,w,x,y,z,i) z+=(w^x^y)+blk(i)+0xCA62C1D6+rol(v,5);w=rol(w,30);
/* Hash a single 512-bit block. This is the core of the algorithm. */
void SHA1Transform(uint32_t state[5], const unsigned char buffer[64])
{
uint32_t a, b, c, d, e;
typedef union {
unsigned char c[64];
uint32_t l[16];
} CHAR64LONG16;
#ifdef SHA1HANDSOFF
CHAR64LONG16 block[1]; /* use array to appear as a pointer */
memcpy(block, buffer, 64);
#else
/* The following had better never be used because it causes the
* pointer-to-const buffer to be cast into a pointer to non-const.
* And the result is written through. I threw a "const" in, hoping
* this will cause a diagnostic.
*/
CHAR64LONG16* block = (const CHAR64LONG16*)buffer;
#endif
/* Copy context->state[] to working vars */
a = state[0];
b = state[1];
c = state[2];
d = state[3];
e = state[4];
/* 4 rounds of 20 operations each. Loop unrolled. */
R0(a,b,c,d,e, 0); R0(e,a,b,c,d, 1); R0(d,e,a,b,c, 2); R0(c,d,e,a,b, 3);
R0(b,c,d,e,a, 4); R0(a,b,c,d,e, 5); R0(e,a,b,c,d, 6); R0(d,e,a,b,c, 7);
R0(c,d,e,a,b, 8); R0(b,c,d,e,a, 9); R0(a,b,c,d,e,10); R0(e,a,b,c,d,11);
R0(d,e,a,b,c,12); R0(c,d,e,a,b,13); R0(b,c,d,e,a,14); R0(a,b,c,d,e,15);
R1(e,a,b,c,d,16); R1(d,e,a,b,c,17); R1(c,d,e,a,b,18); R1(b,c,d,e,a,19);
R2(a,b,c,d,e,20); R2(e,a,b,c,d,21); R2(d,e,a,b,c,22); R2(c,d,e,a,b,23);
R2(b,c,d,e,a,24); R2(a,b,c,d,e,25); R2(e,a,b,c,d,26); R2(d,e,a,b,c,27);
R2(c,d,e,a,b,28); R2(b,c,d,e,a,29); R2(a,b,c,d,e,30); R2(e,a,b,c,d,31);
R2(d,e,a,b,c,32); R2(c,d,e,a,b,33); R2(b,c,d,e,a,34); R2(a,b,c,d,e,35);
R2(e,a,b,c,d,36); R2(d,e,a,b,c,37); R2(c,d,e,a,b,38); R2(b,c,d,e,a,39);
R3(a,b,c,d,e,40); R3(e,a,b,c,d,41); R3(d,e,a,b,c,42); R3(c,d,e,a,b,43);
R3(b,c,d,e,a,44); R3(a,b,c,d,e,45); R3(e,a,b,c,d,46); R3(d,e,a,b,c,47);
R3(c,d,e,a,b,48); R3(b,c,d,e,a,49); R3(a,b,c,d,e,50); R3(e,a,b,c,d,51);
R3(d,e,a,b,c,52); R3(c,d,e,a,b,53); R3(b,c,d,e,a,54); R3(a,b,c,d,e,55);
R3(e,a,b,c,d,56); R3(d,e,a,b,c,57); R3(c,d,e,a,b,58); R3(b,c,d,e,a,59);
R4(a,b,c,d,e,60); R4(e,a,b,c,d,61); R4(d,e,a,b,c,62); R4(c,d,e,a,b,63);
R4(b,c,d,e,a,64); R4(a,b,c,d,e,65); R4(e,a,b,c,d,66); R4(d,e,a,b,c,67);
R4(c,d,e,a,b,68); R4(b,c,d,e,a,69); R4(a,b,c,d,e,70); R4(e,a,b,c,d,71);
R4(d,e,a,b,c,72); R4(c,d,e,a,b,73); R4(b,c,d,e,a,74); R4(a,b,c,d,e,75);
R4(e,a,b,c,d,76); R4(d,e,a,b,c,77); R4(c,d,e,a,b,78); R4(b,c,d,e,a,79);
/* Add the working vars back into context.state[] */
state[0] += a;
state[1] += b;
state[2] += c;
state[3] += d;
state[4] += e;
/* Wipe variables */
a = b = c = d = e = 0;
#ifdef SHA1HANDSOFF
memset(block, '\0', sizeof(block));
#endif
}
/* SHA1Init - Initialize new context */
void SHA1Init(SHA1_CTX* context)
{
/* SHA1 initialization constants */
context->state[0] = 0x67452301;
context->state[1] = 0xEFCDAB89;
context->state[2] = 0x98BADCFE;
context->state[3] = 0x10325476;
context->state[4] = 0xC3D2E1F0;
context->count[0] = context->count[1] = 0;
}
/* Run your data through this. */
void SHA1Update(SHA1_CTX* context, const unsigned char* data, uint32_t len)
{
uint32_t i, j;
j = context->count[0];
if ((context->count[0] += len << 3) < j)
context->count[1]++;
context->count[1] += (len>>29);
j = (j >> 3) & 63;
if ((j + len) > 63) {
memcpy(&context->buffer[j], data, (i = 64-j));
SHA1Transform(context->state, context->buffer);
for ( ; i + 63 < len; i += 64) {
SHA1Transform(context->state, &data[i]);
}
j = 0;
}
else i = 0;
memcpy(&context->buffer[j], &data[i], len - i);
}
/* Add padding and return the message digest. */
void SHA1Final(unsigned char digest[20], SHA1_CTX* context)
{
unsigned i;
unsigned char finalcount[8];
unsigned char c;
#if 0 /* untested "improvement" by DHR */
/* Convert context->count to a sequence of bytes
* in finalcount. Second element first, but
* big-endian order within element.
* But we do it all backwards.
*/
unsigned char *fcp = &finalcount[8];
for (i = 0; i < 2; i++)
{
uint32_t t = context->count[i];
int j;
for (j = 0; j < 4; t >>= 8, j++)
*--fcp = (unsigned char) t;
}
#else
for (i = 0; i < 8; i++) {
finalcount[i] = (unsigned char)((context->count[(i >= 4 ? 0 : 1)]
>> ((3-(i & 3)) * 8) ) & 255); /* Endian independent */
}
#endif
c = 0200;
SHA1Update(context, &c, 1);
while ((context->count[0] & 504) != 448) {
c = 0000;
SHA1Update(context, &c, 1);
}
SHA1Update(context, finalcount, 8); /* Should cause a SHA1Transform() */
for (i = 0; i < 20; i++) {
digest[i] = (unsigned char)
((context->state[i>>2] >> ((3-(i & 3)) * 8) ) & 255);
}
/* Wipe variables */
memset(context, '\0', sizeof(*context));
memset(&finalcount, '\0', sizeof(finalcount));
}
/* ================ end of sha1.c ================ */
// DCC-EX Removed: #endif

View File

@ -1,26 +0,0 @@
// For DCC-EX: This file downloaded from:
// https://github.com/Links2004/arduinoWebSockets
// All due credit to Steve Reid
/* ================ sha1.h ================ */
/*
SHA-1 in C
By Steve Reid <steve@edmweb.com>
100% Public Domain
*/
// DCC-EX REMOVED #if !defined(ESP8266) && !defined(ESP32)
#ifndef libsha1_h
#define libsha1_h
typedef struct {
uint32_t state[5];
uint32_t count[2];
unsigned char buffer[64];
} SHA1_CTX;
void SHA1Transform(uint32_t state[5], const unsigned char buffer[64]);
void SHA1Init(SHA1_CTX* context);
void SHA1Update(SHA1_CTX* context, const unsigned char* data, uint32_t len);
void SHA1Final(unsigned char digest[20], SHA1_CTX* context);
#endif

View File

@ -1,17 +1,16 @@
ECHO ON
FOR /F "delims=" %%i IN ('dir %TMP%\arduino\sketches\CommandStation-EX.ino.elf /s /b /o-D') DO SET ELF=%%i
SET DUMP=%TEMP%\OBJDUMP.txt
echo Most recent subfolder: %ELF% >%DUMP%
FOR /F "delims=" %%i IN ('dir %TMP%\arduino_build_* /b /ad-h /t:c /od') DO SET a=%%i
echo Most recent subfolder: %a% >%TMP%\OBJDUMP_%a%.txt
SET ELF=%TMP%\%a%\CommandStation-EX.ino.elf
set PATH="C:\Program Files (x86)\Arduino\hardware\tools\avr\bin\";%PATH%
avr-objdump --private=mem-usage %ELF% >>%DUMP%
ECHO ++++++++++++++++++++++++++++++++++ >>%DUMP%
avr-objdump -x -C %ELF% | find ".text" | sort /+25 /R >>%DUMP%
ECHO ++++++++++++++++++++++++++++++++++ >>%DUMP%
avr-objdump -x -C %ELF% | find ".data" | sort /+25 /R >>%DUMP%
ECHO ++++++++++++++++++++++++++++++++++ >>%DUMP%
avr-objdump -x -C %ELF% | find ".bss" | sort /+25 /R >>%DUMP%
ECHO ++++++++++++++++++++++++++++++++++ >>%DUMP%
avr-objdump -D -S %ELF% >>%DUMP%
%DUMP%
avr-objdump --private=mem-usage %ELF% >>%TMP%\OBJDUMP_%a%.txt
ECHO ++++++++++++++++++++++++++++++++++ >>%TMP%\OBJDUMP_%a%.txt
avr-objdump -x -C %ELF% | find ".text" | sort /+25 /R >>%TMP%\OBJDUMP_%a%.txt
ECHO ++++++++++++++++++++++++++++++++++ >>%TMP%\OBJDUMP_%a%.txt
avr-objdump -x -C %ELF% | find ".data" | sort /+25 /R >>%TMP%\OBJDUMP_%a%.txt
ECHO ++++++++++++++++++++++++++++++++++ >>%TMP%\OBJDUMP_%a%.txt
avr-objdump -x -C %ELF% | find ".bss" | sort /+25 /R >>%TMP%\OBJDUMP_%a%.txt
ECHO ++++++++++++++++++++++++++++++++++ >>%TMP%\OBJDUMP_%a%.txt
avr-objdump -D -S %ELF% >>%TMP%\OBJDUMP_%a%.txt
%TMP%\OBJDUMP_%a%.txt
EXIT

View File

@ -11,11 +11,11 @@
[platformio]
default_envs =
mega2560
; uno
; nano
; ESP32
; Nucleo-F411RE
; Nucleo-F446RE
uno
nano
ESP32
Nucleo-F411RE
Nucleo-F446RE
src_dir = .
include_dir = .
@ -96,6 +96,7 @@ lib_deps =
${env.lib_deps}
arduino-libraries/Ethernet
SPI
MDNS_Generic
lib_ignore = WiFi101
WiFi101_Generic
@ -114,6 +115,7 @@ framework = arduino
lib_deps =
${env.lib_deps}
arduino-libraries/Ethernet
MDNS_Generic
SPI
lib_ignore = WiFi101
WiFi101_Generic
@ -192,7 +194,7 @@ monitor_speed = 115200
monitor_echo = yes
[env:Nucleo-F411RE]
platform = ststm32 @ 19.0.0
platform = ststm32 @ 17.6.0
board = nucleo_f411re
framework = arduino
lib_deps = ${env.lib_deps}
@ -201,7 +203,7 @@ monitor_speed = 115200
monitor_echo = yes
[env:Nucleo-F446RE]
platform = ststm32 @ 19.0.0
platform = ststm32 @ 17.6.0
board = nucleo_f446re
framework = arduino
lib_deps = ${env.lib_deps}
@ -213,7 +215,7 @@ monitor_echo = yes
; tested as yet
;
[env:Nucleo-F401RE]
platform = ststm32 @ 19.0.0
platform = ststm32 @ 17.6.0
board = nucleo_f401re
framework = arduino
lib_deps = ${env.lib_deps}
@ -226,7 +228,7 @@ monitor_echo = yes
; installed before you can let PlatformIO see this
;
; [env:Nucleo-F413ZH]
; platform = ststm32 @ 19.0.0
; platform = ststm32 @ 17.6.0
; board = nucleo_f413zh
; framework = arduino
; lib_deps = ${env.lib_deps}
@ -238,7 +240,7 @@ monitor_echo = yes
; installed before you can let PlatformIO see this
;
[env:Nucleo-F446ZE]
platform = ststm32 @ 19.0.0
platform = ststm32 @ 17.6.0
board = nucleo_f446ze
framework = arduino
lib_deps = ${env.lib_deps}
@ -250,7 +252,7 @@ monitor_echo = yes
; installed before you can let PlatformIO see this
;
; [env:Nucleo-F412ZG]
; platform = ststm32 @ 19.0.0
; platform = ststm32 @ 17.6.0
; board = nucleo_f412zg
; framework = arduino
; lib_deps = ${env.lib_deps}
@ -259,40 +261,46 @@ monitor_echo = yes
; monitor_echo = yes
; upload_protocol = stlink
; Experimental - Ethernet beta test
; Experimental - Ethernet work still in progress
;
[env:Nucleo-F429ZI]
platform = ststm32 @ 19.0.0
platform = ststm32 @ 17.6.0
board = nucleo_f429zi
framework = arduino
lib_deps = ${env.lib_deps}
stm32duino/STM32Ethernet @ ^1.4.0
stm32duino/STM32duino LwIP @ ^2.1.3
MDNS_Generic
lib_ignore = WiFi101
WiFi101_Generic
WiFiEspAT
WiFiMulti_Generic
WiFiNINA_Generic
build_flags = -std=c++17 -Os -g2 -Wunused-variable -DCUSTOM_PERIPHERAL_PINS
build_flags = -std=c++17 -Os -g2 -Wunused-variable
monitor_speed = 115200
monitor_echo = yes
upload_protocol = stlink
; Experimental - Ethernet beta test
; Experimental - Ethernet work still in progress
;
[env:Nucleo-F439ZI]
platform = ststm32 @ 19.0.0
board = nucleo_f439zi
platform = ststm32 @ 17.6.0
; board = nucleo_f439zi
; Temporarily treat it as an F429ZI (they are code compatible) until
; the PR to PlatformIO to update the F439ZI JSON file is available
; PMA - 28-Sep-2024
board = nucleo_f429zi
framework = arduino
lib_deps = ${env.lib_deps}
stm32duino/STM32Ethernet @ ^1.4.0
stm32duino/STM32duino LwIP @ ^2.1.3
MDNS_Generic
lib_ignore = WiFi101
WiFi101_Generic
WiFiEspAT
WiFiMulti_Generic
WiFiNINA_Generic
build_flags = -std=c++17 -Os -g2 -Wunused-variable -DCUSTOM_PERIPHERAL_PINS
build_flags = -std=c++17 -Os -g2 -Wunused-variable
monitor_speed = 115200
monitor_echo = yes
upload_protocol = stlink

View File

@ -3,34 +3,12 @@
#include "StringFormatter.h"
#define VERSION "5.5.15"
// 5.5.15 - Support for F429ZI/F329ZI
// - Own mDNS support for (wired) Ethernet
// 5.5.14 - DCC Non-blocking packet queue with priority
// 5.5.13 - Update STM32duino core to v19.0.0. for updated PeripheralPins.c in preparation for F429/439ZI Ethernet support
// 5.5.12 - Websocket support (wifi only)
// 5.5.11 - (5.4.2) accessory command reverse
// 5.5.10 - CamParser fix
// 5.5.9 - (5.4.3) fix changeFn for functions 29..31
// 5.5.8 - EXSensorCam clean up to match other filters and
// - avoid need for config.h settings
// - Test: IO_I2CDFPlayer.h inserted 10mS deleay in Init_SC16IS752() just after soft-reset for board with 1.8432 Mhz xtal
// - IO_I2CDFPlayer.h: fixed 2 compiler errors as the compilers are getting stricter
// 5.5.7 - ESP32 bugfix packet buffer race (as 5.4.1)
// 5.5.6 - Fix ESP32 build bug caused by include reference loop
// 5.5.5 - Railcom implementation with IO_I2CRailcom driver
// - response analysis and block management.
// - <r locoid cv> POM read using Railcom.
// - See Release_notes/Railcom.md
// 5.5.4 - Split ESP32 from DCCWaveform to DCCWaveformRMT
// - Railcom Cutout control (DCCTimerAVR Mega only so far)
// 5.5.3 - EXRAIL ESTOPALL,XPOM,
// - Bugfix RESERVE to cause ESTOP.(was STOP)
// - Correct direction sync after manual throttle change.
// - plus ONBLOCKENTER/EXIT in preparation for Railcom
// 5.5.2 - DS1307 Real Time clock
// 5.5.1 - Momentum
// 5.5.0 - New version on devel
#define VERSION "5.4.7"
// 5.4.7 - Bugfix: EXRAIL fix CLEAR_ALL_STASH
// 5.4.6 - Bugfix: Do not drop further commands in same packet
// 5.4.5 - ESP32: Better detection of correct IDF version
// - track power is always turned on after setJoin() not by setJoin()
// 5.4.4 - bugfix in parser, input buffer overrun and trailing > that did break <+>
// 5.4.3 - bugfix changeFn for functions 29..31
// 5.4.2 - Reversed turnout bugfix
// 5.4.1 - ESP32 bugfix packet buffer race