1
0
mirror of https://github.com/DCC-EX/CommandStation-EX.git synced 2024-11-23 16:16:13 +01:00

Compare commits

..

1 Commits

Author SHA1 Message Date
Kcsmith0708
8efd3a310b
Merge 04f0f56348 into fe9b1da8a3 2024-02-18 04:30:12 -07:00
27 changed files with 162 additions and 346 deletions

View File

@ -310,11 +310,6 @@ void CommandDistributor::broadcastRaw(clientType type, char * msg) {
broadcastReply(type, F("%s"),msg); broadcastReply(type, F("%s"),msg);
} }
void CommandDistributor::broadcastMessage(char * message) {
broadcastReply(COMMAND_TYPE, F("<m \"%s\">\n"),message);
broadcastReply(WITHROTTLE_TYPE, F("Hm%s\n"),message);
}
void CommandDistributor::broadcastTrackState(const FSH* format, byte trackLetter, const FSH *modename, int16_t dcAddr) { void CommandDistributor::broadcastTrackState(const FSH* format, byte trackLetter, const FSH *modename, int16_t dcAddr) {
broadcastReply(COMMAND_TYPE, format, trackLetter, modename, dcAddr); broadcastReply(COMMAND_TYPE, format, trackLetter, modename, dcAddr);
} }

View File

@ -60,7 +60,6 @@ public :
static void forget(byte clientId); static void forget(byte clientId);
static void broadcastRouteState(uint16_t routeId,byte state); static void broadcastRouteState(uint16_t routeId,byte state);
static void broadcastRouteCaption(uint16_t routeId,const FSH * caption); static void broadcastRouteCaption(uint16_t routeId,const FSH * caption);
static void broadcastMessage(char * message);
// Handling code for virtual LCD receiver. // Handling code for virtual LCD receiver.
static Print * getVirtualLCDSerial(byte screen, byte row); static Print * getVirtualLCDSerial(byte screen, byte row);

View File

@ -65,9 +65,6 @@
#ifdef EXRAIL_WARNING #ifdef EXRAIL_WARNING
#warning You have myAutomation.h but your hardware has not enough memory to do that, so EX-RAIL DISABLED #warning You have myAutomation.h but your hardware has not enough memory to do that, so EX-RAIL DISABLED
#endif #endif
// compile time check, passwords 1 to 7 chars do not work, so do not try to compile with them at all
// remember trailing '\0', sizeof("") == 1.
#define PASSWDCHECK(S) static_assert(sizeof(S) == 1 || sizeof(S) > 8, "Password shorter than 8 chars")
void setup() void setup()
{ {
@ -105,12 +102,10 @@ void setup()
// Start Ethernet if it exists // Start Ethernet if it exists
#ifndef ARDUINO_ARCH_ESP32 #ifndef ARDUINO_ARCH_ESP32
#if WIFI_ON #if WIFI_ON
PASSWDCHECK(WIFI_PASSWORD); // compile time check
WifiInterface::setup(WIFI_SERIAL_LINK_SPEED, F(WIFI_SSID), F(WIFI_PASSWORD), F(WIFI_HOSTNAME), IP_PORT, WIFI_CHANNEL, WIFI_FORCE_AP); WifiInterface::setup(WIFI_SERIAL_LINK_SPEED, F(WIFI_SSID), F(WIFI_PASSWORD), F(WIFI_HOSTNAME), IP_PORT, WIFI_CHANNEL, WIFI_FORCE_AP);
#endif // WIFI_ON #endif // WIFI_ON
#else #else
// ESP32 needs wifi on always // ESP32 needs wifi on always
PASSWDCHECK(WIFI_PASSWORD); // compile time check
WifiESP::setup(WIFI_SSID, WIFI_PASSWORD, WIFI_HOSTNAME, IP_PORT, WIFI_CHANNEL, WIFI_FORCE_AP); WifiESP::setup(WIFI_SSID, WIFI_PASSWORD, WIFI_HOSTNAME, IP_PORT, WIFI_CHANNEL, WIFI_FORCE_AP);
#endif // ARDUINO_ARCH_ESP32 #endif // ARDUINO_ARCH_ESP32

44
DCC.cpp
View File

@ -153,22 +153,6 @@ uint8_t DCC::getThrottleSpeedByte(int cab) {
return speedTable[reg].speedCode; return speedTable[reg].speedCode;
} }
// returns 0 to 7 for frequency
uint8_t DCC::getThrottleFrequency(int cab) {
#if defined(ARDUINO_AVR_UNO)
(void)cab;
return 0;
#else
int reg=lookupSpeedTable(cab);
if (reg<0)
return 0; // use default frequency
// shift out first 29 bits so we have the 3 "frequency bits" left
uint8_t res = (uint8_t)(speedTable[reg].functions >>29);
//DIAG(F("Speed table %d functions %l shifted %d"), reg, speedTable[reg].functions, res);
return res;
#endif
}
// returns direction on loco // returns direction on loco
// or true/forward on "loco not found" // or true/forward on "loco not found"
bool DCC::getThrottleDirection(int cab) { bool DCC::getThrottleDirection(int cab) {
@ -199,55 +183,43 @@ bool DCC::setFn( int cab, int16_t functionNumber, bool on) {
b[nB++] = functionNumber >>7 ; // high order bits b[nB++] = functionNumber >>7 ; // high order bits
} }
DCCWaveform::mainTrack.schedulePacket(b, nB, 4); DCCWaveform::mainTrack.schedulePacket(b, nB, 4);
}
// We use the reminder table up to 28 for normal functions.
// We use 29 to 31 for DC frequency as well so up to 28
// are "real" functions and 29 to 31 are frequency bits
// controlled by function buttons
if (functionNumber > 31)
return true; return true;
}
int reg = lookupSpeedTable(cab); int reg = lookupSpeedTable(cab);
if (reg<0) return false; if (reg<0) return false;
// Take care of functions: // Take care of functions:
// Set state of function // Set state of function
uint32_t previous=speedTable[reg].functions; unsigned long previous=speedTable[reg].functions;
uint32_t funcmask = (1UL<<functionNumber); unsigned long funcmask = (1UL<<functionNumber);
if (on) { if (on) {
speedTable[reg].functions |= funcmask; speedTable[reg].functions |= funcmask;
} else { } else {
speedTable[reg].functions &= ~funcmask; speedTable[reg].functions &= ~funcmask;
} }
if (speedTable[reg].functions != previous) { if (speedTable[reg].functions != previous) {
if (functionNumber <= 28)
updateGroupflags(speedTable[reg].groupFlags, functionNumber); updateGroupflags(speedTable[reg].groupFlags, functionNumber);
CommandDistributor::broadcastLoco(reg); CommandDistributor::broadcastLoco(reg);
} }
return true; return true;
} }
// Flip function state (used from withrottle protocol) // Flip function state
void DCC::changeFn( int cab, int16_t functionNumber) { void DCC::changeFn( int cab, int16_t functionNumber) {
if (cab<=0 || functionNumber>31) return; if (cab<=0 || functionNumber>28) return;
int reg = lookupSpeedTable(cab); int reg = lookupSpeedTable(cab);
if (reg<0) return; if (reg<0) return;
unsigned long funcmask = (1UL<<functionNumber); unsigned long funcmask = (1UL<<functionNumber);
speedTable[reg].functions ^= funcmask; speedTable[reg].functions ^= funcmask;
if (functionNumber <= 28) {
updateGroupflags(speedTable[reg].groupFlags, functionNumber); updateGroupflags(speedTable[reg].groupFlags, functionNumber);
}
CommandDistributor::broadcastLoco(reg); CommandDistributor::broadcastLoco(reg);
} }
// Report function state (used from withrottle protocol) int DCC::getFn( int cab, int16_t functionNumber) {
// returns 0 false, 1 true or -1 for do not know if (cab<=0 || functionNumber>28) return -1; // unknown
int8_t DCC::getFn( int cab, int16_t functionNumber) {
if (cab<=0 || functionNumber>31)
return -1; // unknown
int reg = lookupSpeedTable(cab); int reg = lookupSpeedTable(cab);
if (reg<0) if (reg<0) return -1;
return -1;
unsigned long funcmask = (1UL<<functionNumber); unsigned long funcmask = (1UL<<functionNumber);
return (speedTable[reg].functions & funcmask)? 1 : 0; return (speedTable[reg].functions & funcmask)? 1 : 0;

5
DCC.h
View File

@ -61,14 +61,13 @@ public:
static void setThrottle(uint16_t cab, uint8_t tSpeed, bool tDirection); static void setThrottle(uint16_t cab, uint8_t tSpeed, bool tDirection);
static int8_t getThrottleSpeed(int cab); static int8_t getThrottleSpeed(int cab);
static uint8_t getThrottleSpeedByte(int cab); static uint8_t getThrottleSpeedByte(int cab);
static uint8_t getThrottleFrequency(int cab);
static bool getThrottleDirection(int cab); static bool getThrottleDirection(int cab);
static void writeCVByteMain(int cab, int cv, byte bValue); static void writeCVByteMain(int cab, int cv, byte bValue);
static void writeCVBitMain(int cab, int cv, byte bNum, bool bValue); static void writeCVBitMain(int cab, int cv, byte bNum, bool bValue);
static void setFunction(int cab, byte fByte, byte eByte); static void setFunction(int cab, byte fByte, byte eByte);
static bool setFn(int cab, int16_t functionNumber, bool on); static bool setFn(int cab, int16_t functionNumber, bool on);
static void changeFn(int cab, int16_t functionNumber); static void changeFn(int cab, int16_t functionNumber);
static int8_t getFn(int cab, int16_t functionNumber); static int getFn(int cab, int16_t functionNumber);
static uint32_t getFunctionMap(int cab); static uint32_t getFunctionMap(int cab);
static void updateGroupflags(byte &flags, int16_t functionNumber); static void updateGroupflags(byte &flags, int16_t functionNumber);
static void setAccessory(int address, byte port, bool gate, byte onoff = 2); static void setAccessory(int address, byte port, bool gate, byte onoff = 2);
@ -100,7 +99,7 @@ public:
int loco; int loco;
byte speedCode; byte speedCode;
byte groupFlags; byte groupFlags;
uint32_t functions; unsigned long functions;
}; };
static LOCO speedTable[MAX_LOCOS]; static LOCO speedTable[MAX_LOCOS];
static int lookupSpeedTable(int locoId, bool autoCreate=true); static int lookupSpeedTable(int locoId, bool autoCreate=true);

View File

@ -68,7 +68,7 @@ Once a new OPCODE is decided upon, update this list.
K, Reserved for future use - Potentially Railcom K, Reserved for future use - Potentially Railcom
l, Loco speedbyte/function map broadcast l, Loco speedbyte/function map broadcast
L, Reserved for LCC interface (implemented in EXRAIL) L, Reserved for LCC interface (implemented in EXRAIL)
m, message to throttles broadcast m,
M, Write DCC packet M, Write DCC packet
n, n,
N, N,
@ -283,22 +283,25 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
return; // filterCallback asked us to ignore return; // filterCallback asked us to ignore
case 't': // THROTTLE <t [REGISTER] CAB SPEED DIRECTION> case 't': // THROTTLE <t [REGISTER] CAB SPEED DIRECTION>
{ {
int16_t cab;
int16_t tspeed;
int16_t direction;
if (params==1) { // <t cab> display state if (params==1) { // <t cab> display state
int16_t slot=DCC::lookupSpeedTable(p[0],false); int16_t slot=DCC::lookupSpeedTable(p[0],false);
if (slot>=0) if (slot>=0) {
CommandDistributor::broadcastLoco(slot); DCC::LOCO * sp=&DCC::speedTable[slot];
StringFormatter::send(stream,F("<l %d %d %d %l>\n"),
sp->loco,slot,sp->speedCode,sp->functions);
}
else // send dummy state speed 0 fwd no functions. else // send dummy state speed 0 fwd no functions.
StringFormatter::send(stream,F("<l %d -1 128 0>\n"),p[0]); StringFormatter::send(stream,F("<l %d -1 128 0>\n"),p[0]);
return; return;
} }
int16_t cab;
int16_t tspeed;
int16_t direction;
if (params == 4) if (params == 4)
{ // <t REGISTER CAB SPEED DIRECTION> { // <t REGISTER CAB SPEED DIRECTION>
// ignore register p[0]
cab = p[1]; cab = p[1];
tspeed = p[2]; tspeed = p[2];
direction = p[3]; direction = p[3];
@ -579,13 +582,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
DCC::setThrottle(0,1,1); // this broadcasts speed 1(estop) and sets all reminders to speed 1. DCC::setThrottle(0,1,1); // this broadcasts speed 1(estop) and sets all reminders to speed 1.
return; return;
#ifdef HAS_ENOUGH_MEMORY
case 'c': // SEND METER RESPONSES <c> case 'c': // SEND METER RESPONSES <c>
// No longer useful because of multiple tracks See <JG> and <JI> // No longer useful because of multiple tracks See <JG> and <JI>
if (params>0) break; if (params>0) break;
TrackManager::reportObsoleteCurrent(stream); TrackManager::reportObsoleteCurrent(stream);
return; return;
#endif
case 'Q': // SENSORS <Q> case 'Q': // SENSORS <Q>
Sensor::printAll(stream); Sensor::printAll(stream);
return; return;

View File

@ -87,7 +87,6 @@ class DCCTimer {
static void reset(); static void reset();
private: private:
static void DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency);
static int freeMemory(); static int freeMemory();
static volatile int minimum_free_memory; static volatile int minimum_free_memory;
static const int DCC_SIGNAL_TIME=58; // this is the 58uS DCC 1-bit waveform half-cycle static const int DCC_SIGNAL_TIME=58; // this is the 58uS DCC 1-bit waveform half-cycle

View File

@ -29,7 +29,6 @@
#include <avr/boot.h> #include <avr/boot.h>
#include <avr/wdt.h> #include <avr/wdt.h>
#include "DCCTimer.h" #include "DCCTimer.h"
#include "DIAG.h"
#ifdef DEBUG_ADC #ifdef DEBUG_ADC
#include "TrackManager.h" #include "TrackManager.h"
#endif #endif
@ -190,81 +189,6 @@ void DCCTimer::reset() {
} }
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f);
}
void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) {
#if defined(ARDUINO_AVR_UNO)
// Not worth doin something here as:
// If we are on pin 9 or 10 we are on Timer1 and we can not touch Timer1 as that is our DCC source.
// If we are on pin 5 or 6 we are on Timer 0 ad we can not touch Timer0 as that is millis() etc.
// We are most likely not on pin 3 or 11 as no known motor shield has that as brake.
#endif
#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)
// Speed mapping is done like this:
// No functions buttons: 000 0 -> low 131Hz
// Only F29 pressed 001 1 -> mid 490Hz
// F30 with or w/o F29 01x 2-3 -> high 3400Hz
// F31 with or w/o F29/30 1xx 4-7 -> supersonic 62500Hz
uint8_t abits;
uint8_t bbits;
if (pin == 9 || pin == 10) { // timer 2 is different
if (fbits >= 4)
abits = B00000011;
else
abits = B00000001;
if (fbits >= 4)
bbits = B0001;
else if (fbits >= 2)
bbits = B0010;
else if (fbits == 1)
bbits = B0100;
else // fbits == 0
bbits = B0110;
TCCR2A = (TCCR2A & B11111100) | abits; // set WGM0 and WGM1
TCCR2B = (TCCR2B & B11110000) | bbits; // set WGM2 and 3 bits of prescaler
DIAG(F("Timer 2 A=%x B=%x"), TCCR2A, TCCR2B);
} else { // not timer 9 or 10
abits = B01;
if (fbits >= 4)
bbits = B1001;
else if (fbits >= 2)
bbits = B0010;
else if (fbits == 1)
bbits = B0011;
else
bbits = B0100;
switch (pin) {
// case 9 and 10 taken care of above by if()
case 6:
case 7:
case 8:
// Timer4
TCCR4A = (TCCR4A & B11111100) | abits; // set WGM0 and WGM1
TCCR4B = (TCCR4B & B11100000) | bbits; // set WGM2 and WGM3 and divisor
//DIAG(F("Timer 4 A=%x B=%x"), TCCR4A, TCCR4B);
break;
case 46:
case 45:
case 44:
// Timer5
TCCR5A = (TCCR5A & B11111100) | abits; // set WGM0 and WGM1
TCCR5B = (TCCR5B & B11100000) | bbits; // set WGM2 and WGM3 and divisor
//DIAG(F("Timer 5 A=%x B=%x"), TCCR5A, TCCR5B);
break;
default:
break;
}
}
#endif
}
#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560) #if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)
#define NUM_ADC_INPUTS 16 #define NUM_ADC_INPUTS 16
#else #else

View File

@ -151,26 +151,10 @@ void DCCTimer::reset() {
ESP.restart(); ESP.restart();
} }
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
if (f >= 16)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f);
else if (f == 7)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 62500);
else if (f >= 4)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 32000);
else if (f >= 3)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 16000);
else if (f >= 2)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 3400);
else if (f == 1)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 480);
else
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 131);
}
#include "esp32-hal.h" #include "esp32-hal.h"
#include "soc/soc_caps.h" #include "soc/soc_caps.h"
#ifdef SOC_LEDC_SUPPORT_HS_MODE #ifdef SOC_LEDC_SUPPORT_HS_MODE
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM<<1) #define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM<<1)
#else #else
@ -180,7 +164,7 @@ void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
static int8_t pin_to_channel[SOC_GPIO_PIN_COUNT] = { 0 }; static int8_t pin_to_channel[SOC_GPIO_PIN_COUNT] = { 0 };
static int cnt_channel = LEDC_CHANNELS; static int cnt_channel = LEDC_CHANNELS;
void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency) { void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency) {
if (pin < SOC_GPIO_PIN_COUNT) { if (pin < SOC_GPIO_PIN_COUNT) {
if (pin_to_channel[pin] != 0) { if (pin_to_channel[pin] != 0) {
ledcSetup(pin_to_channel[pin], frequency, 8); ledcSetup(pin_to_channel[pin], frequency, 8);

View File

@ -134,11 +134,6 @@ void DCCTimer::reset() {
while(true){} while(true){}
} }
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
}
void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) {
}
int16_t ADCee::ADCmax() { int16_t ADCee::ADCmax() {
return 4095; return 4095;
} }

View File

@ -165,11 +165,6 @@ void DCCTimer::reset() {
while(true) {}; while(true) {};
} }
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
}
void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) {
}
#define NUM_ADC_INPUTS NUM_ANALOG_INPUTS #define NUM_ADC_INPUTS NUM_ANALOG_INPUTS
uint16_t ADCee::usedpins = 0; uint16_t ADCee::usedpins = 0;

View File

@ -266,23 +266,6 @@ void DCCTimer::reset() {
while(true) {}; while(true) {};
} }
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
if (f >= 16)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f);
else if (f == 7)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 62500);
else if (f >= 4)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 32000);
else if (f >= 3)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 16000);
else if (f >= 2)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 3400);
else if (f == 1)
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 480);
else
DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 131);
}
// TODO: rationalise the size of these... could really use sparse arrays etc. // TODO: rationalise the size of these... could really use sparse arrays etc.
static HardwareTimer * pin_timer[100] = {0}; static HardwareTimer * pin_timer[100] = {0};
static uint32_t channel_frequency[100] = {0}; static uint32_t channel_frequency[100] = {0};
@ -293,7 +276,7 @@ static uint32_t pin_channel[100] = {0};
// sophisticated about detecting any clash between the timer we'd like to use for PWM and the ones // sophisticated about detecting any clash between the timer we'd like to use for PWM and the ones
// currently used for HA so they don't interfere with one another. For now we'll just make PWM // currently used for HA so they don't interfere with one another. For now we'll just make PWM
// work well... then work backwards to integrate with HA mode if we can. // work well... then work backwards to integrate with HA mode if we can.
void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency) void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency)
{ {
if (pin_timer[pin] == NULL) { if (pin_timer[pin] == NULL) {
// Automatically retrieve TIM instance and channel associated to pin // Automatically retrieve TIM instance and channel associated to pin

View File

@ -150,11 +150,6 @@ void DCCTimer::reset() {
SCB_AIRCR = 0x05FA0004; SCB_AIRCR = 0x05FA0004;
} }
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) {
}
void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) {
}
int16_t ADCee::ADCmax() { int16_t ADCee::ADCmax() {
return 4095; return 4095;
} }

View File

@ -669,45 +669,6 @@ void RMFT2::loop2() {
} }
break; break;
case OPCODE_SETFREQ:
// Frequency is default 0, or 1, 2,3
//if (loco) DCC::setFn(loco,operand,true);
switch (operand) {
case 0: // default - all F-s off
if (loco) {
DCC::setFn(loco,29,false);
DCC::setFn(loco,30,false);
DCC::setFn(loco,31,false);
}
break;
case 1:
if (loco) {
DCC::setFn(loco,29,true);
DCC::setFn(loco,30,false);
DCC::setFn(loco,31,false);
}
break;
case 2:
if (loco) {
DCC::setFn(loco,29,false);
DCC::setFn(loco,30,true);
DCC::setFn(loco,31,false);
}
break;
case 3:
if (loco) {
DCC::setFn(loco,29,false);
DCC::setFn(loco,30,false);
DCC::setFn(loco,31,true);
}
break;
default:
; // do nothing
break;
}
break;
case OPCODE_RESUME: case OPCODE_RESUME:
pausingTask=NULL; pausingTask=NULL;
driveLoco(speedo); driveLoco(speedo);
@ -1334,7 +1295,6 @@ void RMFT2::thrungeString(uint32_t strfar, thrunger mode, byte id) {
break; break;
case thrunge_parse: case thrunge_parse:
case thrunge_broadcast: case thrunge_broadcast:
case thrunge_message:
case thrunge_lcd: case thrunge_lcd:
default: // thrunge_lcd+1, ... default: // thrunge_lcd+1, ...
if (!buffer) buffer=new StringBuffer(); if (!buffer) buffer=new StringBuffer();
@ -1372,9 +1332,6 @@ void RMFT2::thrungeString(uint32_t strfar, thrunger mode, byte id) {
case thrunge_withrottle: case thrunge_withrottle:
CommandDistributor::broadcastRaw(CommandDistributor::WITHROTTLE_TYPE,buffer->getString()); CommandDistributor::broadcastRaw(CommandDistributor::WITHROTTLE_TYPE,buffer->getString());
break; break;
case thrunge_message:
CommandDistributor::broadcastMessage(buffer->getString());
break;
case thrunge_lcd: case thrunge_lcd:
LCD(id,F("%s"),buffer->getString()); LCD(id,F("%s"),buffer->getString());
break; break;

View File

@ -51,7 +51,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,
OPCODE_JOIN,OPCODE_UNJOIN,OPCODE_READ_LOCO1,OPCODE_READ_LOCO2, OPCODE_JOIN,OPCODE_UNJOIN,OPCODE_READ_LOCO1,OPCODE_READ_LOCO2,
#endif #endif
OPCODE_POM, OPCODE_POM,
OPCODE_START,OPCODE_SETLOCO,OPCODE_SETFREQ,OPCODE_SENDLOCO,OPCODE_FORGET, OPCODE_START,OPCODE_SETLOCO,OPCODE_SENDLOCO,OPCODE_FORGET,
OPCODE_PAUSE, OPCODE_RESUME,OPCODE_POWEROFF,OPCODE_POWERON, OPCODE_PAUSE, OPCODE_RESUME,OPCODE_POWEROFF,OPCODE_POWERON,
OPCODE_ONCLOSE, OPCODE_ONTHROW, OPCODE_SERVOTURNOUT, OPCODE_PINTURNOUT, OPCODE_ONCLOSE, OPCODE_ONTHROW, OPCODE_SERVOTURNOUT, OPCODE_PINTURNOUT,
OPCODE_PRINT,OPCODE_DCCACTIVATE,OPCODE_ASPECT, OPCODE_PRINT,OPCODE_DCCACTIVATE,OPCODE_ASPECT,
@ -94,7 +94,7 @@ enum thrunger: byte {
thrunge_serial,thrunge_parse, thrunge_serial,thrunge_parse,
thrunge_serial1, thrunge_serial2, thrunge_serial3, thrunge_serial1, thrunge_serial2, thrunge_serial3,
thrunge_serial4, thrunge_serial5, thrunge_serial6, thrunge_serial4, thrunge_serial5, thrunge_serial6,
thrunge_lcn,thrunge_message, thrunge_lcn,
thrunge_lcd, // Must be last!! thrunge_lcd, // Must be last!!
}; };

View File

@ -97,7 +97,6 @@
#undef LCCX #undef LCCX
#undef LCN #undef LCN
#undef MOVETT #undef MOVETT
#undef MESSAGE
#undef ONACTIVATE #undef ONACTIVATE
#undef ONACTIVATEL #undef ONACTIVATEL
#undef ONAMBER #undef ONAMBER
@ -157,7 +156,6 @@
#undef SET_TRACK #undef SET_TRACK
#undef SET_POWER #undef SET_POWER
#undef SETLOCO #undef SETLOCO
#undef SETFREQ
#undef SIGNAL #undef SIGNAL
#undef SIGNALH #undef SIGNALH
#undef SPEED #undef SPEED
@ -254,7 +252,6 @@
#define LCD(row,msg) #define LCD(row,msg)
#define SCREEN(display,row,msg) #define SCREEN(display,row,msg)
#define LCN(msg) #define LCN(msg)
#define MESSAGE(msg)
#define MOVETT(id,steps,activity) #define MOVETT(id,steps,activity)
#define ONACTIVATE(addr,subaddr) #define ONACTIVATE(addr,subaddr)
#define ONACTIVATEL(linear) #define ONACTIVATEL(linear)
@ -315,7 +312,6 @@
#define SET_TRACK(track,mode) #define SET_TRACK(track,mode)
#define SET_POWER(track,onoff) #define SET_POWER(track,onoff)
#define SETLOCO(loco) #define SETLOCO(loco)
#define SETFREQ(loco,freq)
#define SIGNAL(redpin,amberpin,greenpin) #define SIGNAL(redpin,amberpin,greenpin)
#define SIGNALH(redpin,amberpin,greenpin) #define SIGNALH(redpin,amberpin,greenpin)
#define SPEED(speed) #define SPEED(speed)

View File

@ -95,14 +95,14 @@ constexpr int16_t stuffSize=sizeof(compileTimeSequenceList)/sizeof(int16_t) - 1;
// Compile time function to check for sequence nos. // Compile time function to check for sequence nos.
constexpr bool hasseq(const int16_t value, const int16_t pos=0 ) { constexpr bool hasseq(const int16_t value, const uint16_t pos=0 ) {
return pos>=stuffSize? false : return pos>=stuffSize? false :
compileTimeSequenceList[pos]==value compileTimeSequenceList[pos]==value
|| hasseq(value,pos+1); || hasseq(value,pos+1);
} }
// Compile time function to check for duplicate sequence nos. // Compile time function to check for duplicate sequence nos.
constexpr bool hasdup(const int16_t value, const int16_t pos ) { constexpr bool hasdup(const int16_t value, const uint16_t pos ) {
return pos>=stuffSize? false : return pos>=stuffSize? false :
compileTimeSequenceList[pos]==value compileTimeSequenceList[pos]==value
|| hasseq(value,pos+1) || hasseq(value,pos+1)
@ -118,8 +118,8 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU
// This pass generates no runtime data or code // This pass generates no runtime data or code
#include "EXRAIL2MacroReset.h" #include "EXRAIL2MacroReset.h"
#undef ASPECT #undef ASPECT
#define ASPECT(address,value) static_assert(address <=2044, "invalid Address"); \ #define ASPECT(address,value) static_assert((address & 0x7ff)== address, "invalid Address"); \
static_assert(address>=-3, "Invalid value"); static_assert((value & 0x1F)== value, "Invalid value");
#undef CALL #undef CALL
#define CALL(id) static_assert(hasseq(id),"Sequence not found"); #define CALL(id) static_assert(hasseq(id),"Sequence not found");
#undef FOLLOW #undef FOLLOW
@ -253,9 +253,6 @@ const int StringMacroTracker1=__COUNTER__;
#define PRINT(msg) THRUNGE(msg,thrunge_print) #define PRINT(msg) THRUNGE(msg,thrunge_print)
#undef LCN #undef LCN
#define LCN(msg) THRUNGE(msg,thrunge_lcn) #define LCN(msg) THRUNGE(msg,thrunge_lcn)
#undef MESSAGE
#define MESSAGE(msg) THRUNGE(msg,thrunge_message)
#undef ROUTE_CAPTION #undef ROUTE_CAPTION
#define ROUTE_CAPTION(id,caption) \ #define ROUTE_CAPTION(id,caption) \
case (__COUNTER__ - StringMacroTracker1) : {\ case (__COUNTER__ - StringMacroTracker1) : {\
@ -353,8 +350,6 @@ const FSH * RMFT2::getTurntableDescription(int16_t turntableId) {
#define TT_ADDPOSITION(turntable_id,position,value,home,description...) T_DESC(turntable_id,position,description) #define TT_ADDPOSITION(turntable_id,position,value,home,description...) T_DESC(turntable_id,position,description)
const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) { const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) {
(void)turntableId;
(void)positionId;
#include "myAutomation.h" #include "myAutomation.h"
return NULL; return NULL;
} }
@ -519,7 +514,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define SCREEN(display,id,msg) PRINT(msg) #define SCREEN(display,id,msg) PRINT(msg)
#define STEALTH(code...) PRINT(dummy) #define STEALTH(code...) PRINT(dummy)
#define LCN(msg) PRINT(msg) #define LCN(msg) PRINT(msg)
#define MESSAGE(msg) PRINT(msg)
#define MOVETT(id,steps,activity) OPCODE_SERVO,V(id),OPCODE_PAD,V(steps),OPCODE_PAD,V(EXTurntable::activity),OPCODE_PAD,V(0), #define MOVETT(id,steps,activity) OPCODE_SERVO,V(id),OPCODE_PAD,V(steps),OPCODE_PAD,V(EXTurntable::activity),OPCODE_PAD,V(0),
#define ONACTIVATE(addr,subaddr) OPCODE_ONACTIVATE,V(addr<<2|subaddr), #define ONACTIVATE(addr,subaddr) OPCODE_ONACTIVATE,V(addr<<2|subaddr),
#define ONACTIVATEL(linear) OPCODE_ONACTIVATE,V(linear+3), #define ONACTIVATEL(linear) OPCODE_ONACTIVATE,V(linear+3),
@ -587,7 +581,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define SET_TRACK(track,mode) OPCODE_SET_TRACK,V(TRACK_MODE_##mode <<8 | TRACK_NUMBER_##track), #define SET_TRACK(track,mode) OPCODE_SET_TRACK,V(TRACK_MODE_##mode <<8 | TRACK_NUMBER_##track),
#define SET_POWER(track,onoff) OPCODE_SET_POWER,V(TRACK_POWER_##onoff),OPCODE_PAD, V(TRACK_NUMBER_##track), #define SET_POWER(track,onoff) OPCODE_SET_POWER,V(TRACK_POWER_##onoff),OPCODE_PAD, V(TRACK_NUMBER_##track),
#define SETLOCO(loco) OPCODE_SETLOCO,V(loco), #define SETLOCO(loco) OPCODE_SETLOCO,V(loco),
#define SETFREQ(loco,freq) OPCODE_SETLOCO,V(loco), OPCODE_SETFREQ,V(freq),
#define SIGNAL(redpin,amberpin,greenpin) #define SIGNAL(redpin,amberpin,greenpin)
#define SIGNALH(redpin,amberpin,greenpin) #define SIGNALH(redpin,amberpin,greenpin)
#define SPEED(speed) OPCODE_SPEED,V(speed), #define SPEED(speed) OPCODE_SPEED,V(speed),

View File

@ -1 +1 @@
#define GITHUB_SHA "devel-202403182018Z" #define GITHUB_SHA "devel-202402171752Z"

View File

@ -83,7 +83,6 @@ void EXTurntable::_loop(unsigned long currentMicros) {
// Read returns status as obtained in our loop. // Read returns status as obtained in our loop.
// Return false if our status value is invalid. // Return false if our status value is invalid.
int EXTurntable::_read(VPIN vpin) { int EXTurntable::_read(VPIN vpin) {
(void)vpin; // surpress warning
if (_deviceState == DEVSTATE_FAILED) return 0; if (_deviceState == DEVSTATE_FAILED) return 0;
if (_stepperStatus > 1) { if (_stepperStatus > 1) {
return false; return false;
@ -128,8 +127,6 @@ void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_
vpin, value, activity, duration); vpin, value, activity, duration);
DIAG(F("I2CManager write I2C Address:%d stepsMSB:%d stepsLSB:%d activity:%d"), DIAG(F("I2CManager write I2C Address:%d stepsMSB:%d stepsLSB:%d activity:%d"),
_I2CAddress.toString(), stepsMSB, stepsLSB, activity); _I2CAddress.toString(), stepsMSB, stepsLSB, activity);
#else
(void)duration;
#endif #endif
if (activity < 4) _stepperStatus = 1; // Tell the device driver Turntable-EX is busy if (activity < 4) _stepperStatus = 1; // Tell the device driver Turntable-EX is busy
_previousStatus = _stepperStatus; _previousStatus = _stepperStatus;

View File

@ -325,23 +325,49 @@ uint16_t taurustones[28] = { 165, 175, 196, 220,
220, 196, 175, 165 }; 220, 196, 175, 165 };
#endif #endif
#endif #endif
void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/) { void MotorDriver::setDCSignal(byte speedcode) {
if (brakePin == UNUSED_PIN) if (brakePin == UNUSED_PIN)
return; return;
switch(brakePin) {
#if defined(ARDUINO_AVR_UNO)
// Not worth doin something here as:
// If we are on pin 9 or 10 we are on Timer1 and we can not touch Timer1 as that is our DCC source.
// If we are on pin 5 or 6 we are on Timer 0 ad we can not touch Timer0 as that is millis() etc.
// We are most likely not on pin 3 or 11 as no known motor shield has that as brake.
#endif
#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)
case 9:
case 10:
// Timer2 (is differnet)
TCCR2A = (TCCR2A & B11111100) | B00000001; // set WGM1=0 and WGM0=1 phase correct PWM
TCCR2B = (TCCR2B & B11110000) | B00000110; // set WGM2=0 ; set divisor on timer 2 to 1/256 for 122.55Hz
//DIAG(F("2 A=%x B=%x"), TCCR2A, TCCR2B);
break;
case 6:
case 7:
case 8:
// Timer4
TCCR4A = (TCCR4A & B11111100) | B00000001; // set WGM0=1 and WGM1=0 for normal PWM 8-bit
TCCR4B = (TCCR4B & B11100000) | B00000100; // set WGM2=0 and WGM3=0 for normal PWM 8 bit and div 1/256 for 122.55Hz
break;
case 46:
case 45:
case 44:
// Timer5
TCCR5A = (TCCR5A & B11111100) | B00000001; // set WGM0=1 and WGM1=0 for normal PWM 8-bit
TCCR5B = (TCCR5B & B11100000) | B00000100; // set WGM2=0 and WGM3=0 for normal PWM 8 bit and div 1/256 for 122.55Hz
break;
#endif
default:
break;
}
// spedcoode is a dcc speed & direction // spedcoode is a dcc speed & direction
byte tSpeed=speedcode & 0x7F; // DCC Speed with 0,1 stop and speed steps 2 to 127 byte tSpeed=speedcode & 0x7F; // DCC Speed with 0,1 stop and speed steps 2 to 127
byte tDir=speedcode & 0x80; byte tDir=speedcode & 0x80;
byte brake; byte brake;
if (tSpeed <= 1) brake = 255;
else if (tSpeed >= 127) brake = 0;
else brake = 2 * (128-tSpeed);
if (invertBrake)
brake=255-brake;
{ // new block because of variable f
#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32) #if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32)
int f = frequency; {
int f = 131;
#ifdef VARIABLE_TONES #ifdef VARIABLE_TONES
if (tSpeed > 2) { if (tSpeed > 2) {
if (tSpeed <= 58) { if (tSpeed <= 58) {
@ -349,15 +375,19 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/)
} }
} }
#endif #endif
//DIAG(F("Brake pin %d freqency %d"), brakePin, f); DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup
DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency }
#endif
if (tSpeed <= 1) brake = 255;
else if (tSpeed >= 127) brake = 0;
else brake = 2 * (128-tSpeed);
if (invertBrake)
brake=255-brake;
#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32)
DCCTimer::DCCEXanalogWrite(brakePin,brake); DCCTimer::DCCEXanalogWrite(brakePin,brake);
#else // all AVR here #else
DCCTimer::DCCEXanalogWriteFrequency(brakePin, frequency); // frequency steps
analogWrite(brakePin,brake); analogWrite(brakePin,brake);
#endif #endif
}
//DIAG(F("DCSignal %d"), speedcode); //DIAG(F("DCSignal %d"), speedcode);
if (HAVE_PORTA(fastSignalPin.shadowinout == &PORTA)) { if (HAVE_PORTA(fastSignalPin.shadowinout == &PORTA)) {
noInterrupts(); noInterrupts();
@ -406,26 +436,58 @@ void MotorDriver::throttleInrush(bool on) {
return; return;
if ( !(trackMode & (TRACK_MODE_MAIN | TRACK_MODE_PROG | TRACK_MODE_EXT))) if ( !(trackMode & (TRACK_MODE_MAIN | TRACK_MODE_PROG | TRACK_MODE_EXT)))
return; return;
byte duty = on ? 207 : 0; // duty of 81% at 62500Hz this gives pauses of 3usec byte duty = on ? 208 : 0;
if (invertBrake) if (invertBrake)
duty = 255-duty; duty = 255-duty;
#if defined(ARDUINO_ARCH_ESP32) #if defined(ARDUINO_ARCH_ESP32)
if(on) { if(on) {
DCCTimer::DCCEXanalogWrite(brakePin,duty); DCCTimer::DCCEXanalogWrite(brakePin,duty);
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max DCCTimer::DCCEXanalogWriteFrequency(brakePin, 62500);
} else { } else {
ledcDetachPin(brakePin); ledcDetachPin(brakePin);
} }
#elif defined(ARDUINO_ARCH_STM32) #elif defined(ARDUINO_ARCH_STM32)
if(on) { if(on) {
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max DCCTimer::DCCEXanalogWriteFrequency(brakePin, 62500);
DCCTimer::DCCEXanalogWrite(brakePin,duty); DCCTimer::DCCEXanalogWrite(brakePin,duty);
} else { } else {
pinMode(brakePin, OUTPUT); pinMode(brakePin, OUTPUT);
} }
#else // all AVR here #else
if(on){ if(on){
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max switch(brakePin) {
#if defined(ARDUINO_AVR_UNO)
// Not worth doin something here as:
// If we are on pin 9 or 10 we are on Timer1 and we can not touch Timer1 as that is our DCC source.
// If we are on pin 5 or 6 we are on Timer 0 ad we can not touch Timer0 as that is millis() etc.
// We are most likely not on pin 3 or 11 as no known motor shield has that as brake.
#endif
#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)
case 9:
case 10:
// Timer2 (is different)
TCCR2A = (TCCR2A & B11111100) | B00000011; // set WGM0=1 and WGM1=1 for fast PWM
TCCR2B = (TCCR2B & B11110000) | B00000001; // set WGM2=0 and prescaler div=1 (max)
DIAG(F("2 A=%x B=%x"), TCCR2A, TCCR2B);
break;
case 6:
case 7:
case 8:
// Timer4
TCCR4A = (TCCR4A & B11111100) | B00000001; // set WGM0=1 and WGM1=0 for fast PWM 8-bit
TCCR4B = (TCCR4B & B11100000) | B00001001; // set WGM2=1 and WGM3=0 for fast PWM 8 bit and div=1 (max)
break;
case 46:
case 45:
case 44:
// Timer5
TCCR5A = (TCCR5A & B11111100) | B00000001; // set WGM0=1 and WGM1=0 for fast PWM 8-bit
TCCR5B = (TCCR5B & B11100000) | B00001001; // set WGM2=1 and WGM3=0 for fast PWM 8 bit and div=1 (max)
break;
#endif
default:
break;
}
} }
analogWrite(brakePin,duty); analogWrite(brakePin,duty);
#endif #endif

View File

@ -34,15 +34,9 @@ template<class T> inline T operator| (T a, T b) { return (T)((int)a | (int)b); }
template<class T> inline T operator& (T a, T b) { return (T)((int)a & (int)b); } template<class T> inline T operator& (T a, T b) { return (T)((int)a & (int)b); }
template<class T> inline T operator^ (T a, T b) { return (T)((int)a ^ (int)b); } template<class T> inline T operator^ (T a, T b) { return (T)((int)a ^ (int)b); }
enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PROG = 4, enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PROG = 4,
TRACK_MODE_DC = 8, TRACK_MODE_EXT = 16, TRACK_MODE_DC = 8, TRACK_MODE_EXT = 16, TRACK_MODE_BOOST = 32,
#ifdef ARDUINO_ARCH_ESP32 TRACK_MODE_ALL = 62, // only to operate all tracks
TRACK_MODE_BOOST = 32, TRACK_MODE_INV = 64, TRACK_MODE_DCX = 72 /*DC + INV*/, TRACK_MODE_AUTOINV = 128};
#else
TRACK_MODE_BOOST = 0,
#endif
TRACK_MODE_ALL = TRACK_MODE_MAIN|TRACK_MODE_PROG|TRACK_MODE_DC|TRACK_MODE_EXT|TRACK_MODE_BOOST,
TRACK_MODE_INV = 64,
TRACK_MODE_DCX = TRACK_MODE_DC|TRACK_MODE_INV, TRACK_MODE_AUTOINV = 128};
#define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH #define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH
#define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW #define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW
@ -193,7 +187,7 @@ class MotorDriver {
} }
}; };
inline pinpair getSignalPin() { return pinpair(signalPin,signalPin2); }; inline pinpair getSignalPin() { return pinpair(signalPin,signalPin2); };
void setDCSignal(byte speedByte, uint8_t frequency=0); void setDCSignal(byte speedByte);
void throttleInrush(bool on); void throttleInrush(bool on);
inline void detachDCSignal() { inline void detachDCSignal() {
#if defined(__arm__) #if defined(__arm__)

View File

@ -1,7 +1,7 @@
/* /*
* © 2022-2023 Paul M. Antoine * © 2022-2023 Paul M. Antoine
* © 2021 Fred Decker * © 2021 Fred Decker
* © 2020-2024 Harald Barth * © 2020-2023 Harald Barth
* (c) 2020 Chris Harlow. All rights reserved. * (c) 2020 Chris Harlow. All rights reserved.
* (c) 2021 Fred Decker. All rights reserved. * (c) 2021 Fred Decker. All rights reserved.
* (c) 2020 Harald Barth. All rights reserved. * (c) 2020 Harald Barth. All rights reserved.
@ -57,10 +57,6 @@
// of the brake pin on the motor bridge is inverted // of the brake pin on the motor bridge is inverted
// (HIGH == release brake) // (HIGH == release brake)
// You can have a CS wihout any possibility to do any track signal.
// That's strange but possible.
#define NO_SHIELD F("No shield at all")
// Arduino STANDARD Motor Shield, used on different architectures: // Arduino STANDARD Motor Shield, used on different architectures:
#if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32) #if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32)

View File

@ -1,6 +1,6 @@
/* /*
* © 2022 Chris Harlow * © 2022 Chris Harlow
* © 2022-2024 Harald Barth * © 2022,2023 Harald Barth
* © 2023 Colin Murdoch * © 2023 Colin Murdoch
* All rights reserved. * All rights reserved.
* *
@ -19,7 +19,6 @@
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>. * along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/ */
#include "defines.h"
#include "TrackManager.h" #include "TrackManager.h"
#include "FSH.h" #include "FSH.h"
#include "DCCWaveform.h" #include "DCCWaveform.h"
@ -41,7 +40,7 @@
MotorDriver * TrackManager::track[MAX_TRACKS]; MotorDriver * TrackManager::track[MAX_TRACKS];
int16_t TrackManager::trackDCAddr[MAX_TRACKS]; int16_t TrackManager::trackDCAddr[MAX_TRACKS];
int8_t TrackManager::lastTrack=-1; byte TrackManager::lastTrack=0;
bool TrackManager::progTrackSyncMain=false; bool TrackManager::progTrackSyncMain=false;
bool TrackManager::progTrackBoosted=false; bool TrackManager::progTrackBoosted=false;
int16_t TrackManager::joinRelay=UNUSED_PIN; int16_t TrackManager::joinRelay=UNUSED_PIN;
@ -183,7 +182,7 @@ void TrackManager::setDCSignal(int16_t cab, byte speedbyte) {
FOR_EACH_TRACK(t) { FOR_EACH_TRACK(t) {
if (trackDCAddr[t]!=cab && cab != 0) continue; if (trackDCAddr[t]!=cab && cab != 0) continue;
if (track[t]->getMode() & TRACK_MODE_DC) if (track[t]->getMode() & TRACK_MODE_DC)
track[t]->setDCSignal(speedbyte, DCC::getThrottleFrequency(trackDCAddr[t])); track[t]->setDCSignal(speedbyte);
} }
} }
@ -219,7 +218,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
if (mode & TRACK_MODE_BOOST) { if (mode & TRACK_MODE_BOOST) {
//DIAG(F("Track=%c mode boost pin %d"),trackToSet+'A', p.pin); //DIAG(F("Track=%c mode boost pin %d"),trackToSet+'A', p.pin);
pinMode(BOOSTER_INPUT, INPUT); pinMode(BOOSTER_INPUT, INPUT);
gpio_matrix_in(BOOSTER_INPUT, SIG_IN_FUNC228_IDX, false); //pads 224 to 228 available as loopback gpio_matrix_in(26, SIG_IN_FUNC228_IDX, false); //pads 224 to 228 available as loopback
gpio_matrix_out(p.pin, SIG_IN_FUNC228_IDX, false, false); gpio_matrix_out(p.pin, SIG_IN_FUNC228_IDX, false, false);
if (p.invpin != UNUSED_PIN) { if (p.invpin != UNUSED_PIN) {
gpio_matrix_out(p.invpin, SIG_IN_FUNC228_IDX, true /*inverted*/, false); gpio_matrix_out(p.invpin, SIG_IN_FUNC228_IDX, true /*inverted*/, false);
@ -329,8 +328,8 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
} }
void TrackManager::applyDCSpeed(byte t) { void TrackManager::applyDCSpeed(byte t) {
track[t]->setDCSignal(DCC::getThrottleSpeedByte(trackDCAddr[t]), uint8_t speedByte=DCC::getThrottleSpeedByte(trackDCAddr[t]);
DCC::getThrottleFrequency(trackDCAddr[t])); track[t]->setDCSignal(speedByte);
} }
bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[]) bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[])
@ -362,8 +361,7 @@ bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[])
if (params==2 && p[1]=="EXT"_hk) // <= id EXT> if (params==2 && p[1]=="EXT"_hk) // <= id EXT>
return setTrackMode(p[0],TRACK_MODE_EXT); return setTrackMode(p[0],TRACK_MODE_EXT);
#ifdef BOOSTER_INPUT #ifdef BOOSTER_INPUT
if (TRACK_MODE_BOOST != 0 && // compile time optimization if (params==2 && p[1]=="BOOST"_hk) // <= id BOOST>
params==2 && p[1]=="BOOST"_hk) // <= id BOOST>
return setTrackMode(p[0],TRACK_MODE_BOOST); return setTrackMode(p[0],TRACK_MODE_BOOST);
#endif #endif
if (params==2 && p[1]=="AUTO"_hk) // <= id AUTO> if (params==2 && p[1]=="AUTO"_hk) // <= id AUTO>
@ -402,11 +400,11 @@ const FSH* TrackManager::getModeName(TRACK_MODE tm) {
modename=F("EXT"); modename=F("EXT");
else if(tm & TRACK_MODE_BOOST) { else if(tm & TRACK_MODE_BOOST) {
if(tm & TRACK_MODE_AUTOINV) if(tm & TRACK_MODE_AUTOINV)
modename=F("BOOST A"); modename=F("B A");
else if (tm & TRACK_MODE_INV) else if (tm & TRACK_MODE_INV)
modename=F("BOOST I"); modename=F("B I");
else else
modename=F("BOOST"); modename=F("B");
} }
else if (tm & TRACK_MODE_DC) { else if (tm & TRACK_MODE_DC) {
if (tm & TRACK_MODE_INV) if (tm & TRACK_MODE_INV)
@ -499,10 +497,6 @@ void TrackManager::setTrackPower(TRACK_MODE trackmodeToMatch, POWERMODE powermod
// Set track power for this track, inependent of mode // Set track power for this track, inependent of mode
void TrackManager::setTrackPower(POWERMODE powermode, byte t) { void TrackManager::setTrackPower(POWERMODE powermode, byte t) {
MotorDriver *driver=track[t]; MotorDriver *driver=track[t];
if (driver == NULL) { // track is not defined at all
DIAG(F("Error: Track %c does not exist"), t+'A');
return;
}
TRACK_MODE trackmode = driver->getMode(); TRACK_MODE trackmode = driver->getMode();
POWERMODE oldpower = driver->getPower(); POWERMODE oldpower = driver->getPower();
if (trackmode & TRACK_MODE_NONE) { if (trackmode & TRACK_MODE_NONE) {
@ -560,17 +554,14 @@ bool TrackManager::getPower(byte t, char s[]) {
return false; return false;
} }
void TrackManager::reportObsoleteCurrent(Print* stream) { void TrackManager::reportObsoleteCurrent(Print* stream) {
// This function is for backward JMRI compatibility only // This function is for backward JMRI compatibility only
// It reports the first track only, as main, regardless of track settings. // It reports the first track only, as main, regardless of track settings.
// <c MeterName value C/V unit min max res warn> // <c MeterName value C/V unit min max res warn>
#ifdef HAS_ENOUGH_MEMORY
int maxCurrent=track[0]->raw2mA(track[0]->getRawCurrentTripValue()); int maxCurrent=track[0]->raw2mA(track[0]->getRawCurrentTripValue());
StringFormatter::send(stream, F("<c CurrentMAIN %d C Milli 0 %d 1 %d>\n"), StringFormatter::send(stream, F("<c CurrentMAIN %d C Milli 0 %d 1 %d>\n"),
track[0]->raw2mA(track[0]->getCurrentRaw(false)), maxCurrent, maxCurrent); track[0]->raw2mA(track[0]->getCurrentRaw(false)), maxCurrent, maxCurrent);
#else
(void)stream;
#endif
} }
void TrackManager::reportCurrent(Print* stream) { void TrackManager::reportCurrent(Print* stream) {

View File

@ -1,6 +1,6 @@
/* /*
* © 2022 Chris Harlow * © 2022 Chris Harlow
* © 2022-2024 Harald Barth * © 2022 Harald Barth
* © 2023 Colin Murdoch * © 2023 Colin Murdoch
* *
* All rights reserved. * All rights reserved.
@ -46,7 +46,7 @@ const byte TRACK_POWER_1=1, TRACK_POWER_ON=1;
class TrackManager { class TrackManager {
public: public:
static void Setup(const FSH * shieldName, static void Setup(const FSH * shieldName,
MotorDriver * track0=NULL, MotorDriver * track0,
MotorDriver * track1=NULL, MotorDriver * track1=NULL,
MotorDriver * track2=NULL, MotorDriver * track2=NULL,
MotorDriver * track3=NULL, MotorDriver * track3=NULL,
@ -108,7 +108,7 @@ class TrackManager {
private: private:
static void addTrack(byte t, MotorDriver* driver); static void addTrack(byte t, MotorDriver* driver);
static int8_t lastTrack; static byte lastTrack;
static byte nextCycleTrack; static byte nextCycleTrack;
static void applyDCSpeed(byte t); static void applyDCSpeed(byte t);

View File

@ -247,9 +247,8 @@ DCCTurntable::DCCTurntable(uint16_t id) : Turntable(id, TURNTABLE_DCC) {}
StringFormatter::send(stream, F("<i %d DCCTURNTABLE>\n"), _turntableData.id); StringFormatter::send(stream, F("<i %d DCCTURNTABLE>\n"), _turntableData.id);
} }
// EX-Turntable specific code for moving to the specified position // EX-Turntable specific code for moving to the specified position
bool DCCTurntable::setPositionInternal(uint8_t position, uint8_t activity) { bool DCCTurntable::setPositionInternal(uint8_t position, uint8_t activity) {
(void) activity;
#ifndef IO_NO_HAL #ifndef IO_NO_HAL
int16_t value = getPositionValue(position); int16_t value = getPositionValue(position);
if (position == 0 || !value) return false; // Return false if it's not a valid position if (position == 0 || !value) return false; // Return false if it's not a valid position
@ -264,6 +263,6 @@ bool DCCTurntable::setPositionInternal(uint8_t position, uint8_t activity) {
(void)position; (void)position;
#endif #endif
return true; return true;
} }
#endif #endif

View File

@ -571,7 +571,7 @@ void WiThrottle::sendRoutes(Print* stream) {
void WiThrottle::sendFunctions(Print* stream, byte loco) { void WiThrottle::sendFunctions(Print* stream, byte loco) {
int16_t locoid=myLocos[loco].cab; int16_t locoid=myLocos[loco].cab;
int fkeys=32; // upper limit (send functions 0 to 31) int fkeys=29;
myLocos[loco].functionToggles=1<<2; // F2 (HORN) is a non-toggle myLocos[loco].functionToggles=1<<2; // F2 (HORN) is a non-toggle
#ifdef EXRAIL_ACTIVE #ifdef EXRAIL_ACTIVE
@ -621,7 +621,7 @@ void WiThrottle::sendFunctions(Print* stream, byte loco) {
#endif #endif
for(int fKey=0; fKey<fkeys; fKey++) { for(int fKey=0; fKey<fkeys; fKey++) {
int8_t fstate=DCC::getFn(locoid,fKey); int fstate=DCC::getFn(locoid,fKey);
if (fstate>=0) StringFormatter::send(stream,F("M%cA%c%d<;>F%d%d\n"),myLocos[loco].throttle,LorS(locoid),locoid,fstate,fKey); if (fstate>=0) StringFormatter::send(stream,F("M%cA%c%d<;>F%d%d\n"),myLocos[loco].throttle,LorS(locoid),locoid,fstate,fKey);
} }
} }

View File

@ -3,13 +3,7 @@
#include "StringFormatter.h" #include "StringFormatter.h"
#define VERSION "5.2.40" #define VERSION "5.2.35"
// 5.2.40 - Allow no shield
// 5.2.39 - Functions for DC frequency: Use func up to F31
// 5.2.38 - Exrail MESSAGE("text") to send a user message to all
// connected throttles (uses <m "text"> and withrottle Hmtext.
// 5.2.37 - Bugfix ESP32: Use BOOSTER_INPUT define
// 5.2.36 - Variable frequency for DC mode
// 5.2.35 - Bugfix: Make DCC Extended Accessories follow RCN-213 // 5.2.35 - Bugfix: Make DCC Extended Accessories follow RCN-213
// 5.2.34 - <A address aspect> Command fopr DCC Extended Accessories // 5.2.34 - <A address aspect> Command fopr DCC Extended Accessories
// - Exrail ASPECT(address,aspect) for above. // - Exrail ASPECT(address,aspect) for above.