1
0
mirror of https://github.com/DCC-EX/CommandStation-EX.git synced 2025-07-29 10:23:45 +02:00

Compare commits

...

61 Commits

Author SHA1 Message Date
Harald Barth
1888073dc2 set lastPowerChange we doing the power on retry after overload 2023-06-19 08:43:50 +02:00
Harald Barth
6dd175f63b fix power change timer micros overflow 2023-06-19 00:33:53 +02:00
Harald Barth
f83be05220 STM32: Use mask as loop variable 2023-06-18 19:26:38 +02:00
Harald Barth
cade89ba16 check ADCee::init() return value 2023-06-18 09:48:15 +02:00
Harald Barth
277825c530 versiontag 2023-06-18 09:01:32 +02:00
Harald Barth
95fe7aafe0 overload detection code cleanup 2023-06-18 08:59:37 +02:00
Harald Barth
f99deb4276 overload detection different timestamps and verbose diag 2023-06-14 22:57:28 +02:00
Harald Barth
f5d4dcb97c new overload detection 2023-06-14 00:58:02 +02:00
Harald Barth
8a69403dda devel release version 4.2.54 2023-06-03 22:01:14 +02:00
Harald Barth
e81d1cc93a Better warnings for pin number errors 2023-05-29 09:48:22 +02:00
Harald Barth
82929245ed char * / flashstring conflict 2023-05-25 14:02:28 +02:00
Harald Barth
db0e0cbf8b Send default function list in jR as well 2023-05-25 10:29:01 +02:00
Harald Barth
803b996e0b Merge branch 'devel' of https://github.com/DCC-EX/CommandStation-EX into devel 2023-05-25 09:29:47 +02:00
Harald Barth
5607ff7167 version 2023-05-25 09:29:42 +02:00
Harald Barth
58e62aaa81 Bug: Withrottle roster list returning empty string vs NULL 2023-05-25 09:27:41 +02:00
Harald Barth
5a9adea2b6 Bug: Withrottle roster list end was not detected 2023-05-25 08:05:07 +02:00
pmantoine
bf136d49e0 Fix Serial ports for Nucleo-144 boards 2023-05-25 08:34:20 +08:00
Harald Barth
50313ebbd2 cast to big enough type 2023-05-24 22:58:21 +02:00
Harald Barth
72bfc6abc7 INT16_MAX missing again 2023-05-24 22:57:43 +02:00
Harald Barth
342d9263d1 time stamp 2023-05-24 13:32:34 +02:00
Harald Barth
20d66fad4e Routes, automations and roster lists: Exclude ID 0 to be presented as available 2023-05-24 13:31:18 +02:00
Harald Barth
be4235e792 Arduino Mega2560: Use timer5 as timer4 for PWM DC 2023-05-24 13:29:20 +02:00
Harald Barth
c22d789513 INT16_MAX was missing at more places 2023-05-23 18:59:03 +02:00
Harald Barth
951a6637f0 INT16_MAX is a better end of array marker than -1 2023-05-23 10:57:45 +02:00
Harald Barth
fdbcbdf418 Do not send default roster entry on withrottle but on JR 2023-05-22 22:51:35 +02:00
Harald Barth
9478c3263d Try to find default roster entry 2023-05-22 16:39:24 +02:00
Harald Barth
16f94ecbdc Restict where what SerialX is used 2023-05-21 20:20:32 +02:00
Harald Barth
b80d7bd517 Pin handling supports pins up to 254 2023-05-21 11:54:46 +02:00
Harald Barth
8786285624 Assume that we have enough HW serials 2023-05-20 23:57:17 +02:00
Harald Barth
132b0773ef Fault pin handling made more straight forward 2023-05-20 23:15:15 +02:00
pmantoine
1a3d295564 Nucleo-F446RE and other serial port updates. 2023-05-20 21:50:20 +08:00
Harald Barth
3b6789ef01 Merge branch 'devel-sabertooth' into devel 2023-05-20 14:59:07 +02:00
Harald Barth
c472f48d93 Experimental support for sabertooth motor controller on ESP32 2023-05-20 14:57:00 +02:00
pmantoine
94e9c2021b Fix config.example.h OLED_DRIVER #define 2023-05-15 11:31:44 +08:00
Harald Barth
9aad2e3206 save another 2 bytes in turnouts if eeprom is disabled 2023-05-09 14:17:30 +02:00
Harald Barth
ecc366cbd1 Merge branch '332-feature-request-add-a-no-programming-option-to-save-ram-on-uno' into devel 2023-05-09 14:11:18 +02:00
pmantoine
f4e3ca7c81 EX8874 entry for SAMD/STM32 2023-05-08 08:32:47 +08:00
Harald Barth
991bda63e0 update to production shield factors 2023-05-08 00:35:00 +02:00
Harald Barth
5164bd143c versions 2023-05-08 00:22:31 +02:00
Harald Barth
3759fc2a1a add checks for broken cab ID 2023-05-08 00:19:59 +02:00
Harald Barth
df7b890758 No EEPROM so you do not need this 2023-05-07 23:58:47 +02:00
Harald Barth
6d802f3a73 estop all locos in list, even last one 2023-05-05 16:14:44 +02:00
Harald Barth
9d953c70b8 use M1 and M2 instead of MD for motor control 2023-05-02 23:51:17 +02:00
Asbelos
6781e44fdd Fix EXRAIL speed issue 2023-05-02 22:02:52 +01:00
Asbelos
a3c9800aba Update version.h 2023-05-02 12:29:03 +01:00
Harald Barth
efdbfcb030 Add serial output for sabertooth controller 2023-05-01 20:18:32 +02:00
Asbelos
28d9843133 Broadcast changes in EXRAIlr 2023-05-01 14:25:45 +01:00
Harald Barth
4eaad2d05b disable more PROG stuff (JOIN/UNJOIN from EXRAIL) 2023-04-23 22:45:47 +02:00
Harald Barth
72d131035e disable more PROG stuff (all hash keywords PROG etc) 2023-04-23 20:24:29 +02:00
peteGSX
2d1e695ac7 Disable <D ACK> 2023-04-20 08:26:17 +10:00
peteGSX
e780c40b34 Disable POM OPCODE 2023-04-20 08:16:32 +10:00
peteGSX
7addb13785 Disable <R> completely 2023-04-20 07:21:32 +10:00
peteGSX
b6f8889e8c Disable most programming functions 2023-04-20 07:08:11 +10:00
Colin Murdoch
33306219c8 Merge branch 'devel' of https://github.com/DCC-EX/CommandStation-EX into devel 2023-04-19 19:46:12 +01:00
Colin Murdoch
d857c4f2e4 Added to Copyright notice
Added my name to copyright notice
2023-04-19 19:45:40 +01:00
Asbelos
70fae16ab3 Correct response to <JA 0> 2023-04-19 11:18:47 +01:00
Harald Barth
f465020e93 Support boards with inverted fault pin 2023-04-17 23:40:48 +02:00
Harald Barth
235bcc9ff0 Merge branch 'devel' into devel-invfault 2023-04-17 23:20:01 +02:00
pmantoine
d2cc60812d Merge ESP32-fixes into DCCTimerESP 2023-04-16 15:40:27 +08:00
pmantoine
75f274e3b7 STM32 unsupported board selection error reporting 2023-04-13 15:27:22 +08:00
Harald Barth
31ecba08d8 faultPin can be inverted (from its inverted sense 2023-03-03 20:51:32 +01:00
29 changed files with 523 additions and 428 deletions

View File

@@ -2,6 +2,7 @@
* © 2022 Harald Barth
* © 2020-2021 Chris Harlow
* © 2020 Gregor Baues
* © 2022 Colin Murdoch
* All rights reserved.
*
* This file is part of CommandStation-EX
@@ -167,7 +168,7 @@ void CommandDistributor::broadcastClockTime(int16_t time, int8_t rate) {
// be safe for both types.
broadcastReply(COMMAND_TYPE, F("<jC %d %d>\n"),time, rate);
#ifdef CD_HANDLE_RING
broadcastReply(WITHROTTLE_TYPE, F("PFT%d<;>%d\n"), time*60, rate);
broadcastReply(WITHROTTLE_TYPE, F("PFT%l<;>%d\n"), (int32_t)time*60, rate);
#endif
}
@@ -204,6 +205,39 @@ int16_t CommandDistributor::retClockTime() {
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;
bool direction = (sp->speedCode & 0x80) !=0; // true for forward
int32_t speed = sp->speedCode & 0x7f;
if (speed == 1) { // emergency stop
if (rampingmode != 1) {
rampingmode = 1;
Serial2.print("R1: 0\r\n");
Serial2.print("R2: 0\r\n");
}
Serial2.print("MD: 0\r\n");
} else {
if (speed != 0) {
// speed is here 2 to 127
speed = (speed - 1) * 1625 / 100;
speed = speed * (direction ? 1 : -1);
// speed is here -2047 to 2047
}
if (rampingmode != 2) {
rampingmode = 2;
Serial2.print("R1: 2047\r\n");
Serial2.print("R2: 2047\r\n");
}
Serial2.print("M1: ");
Serial2.print(speed);
Serial2.print("\r\n");
Serial2.print("M2: ");
Serial2.print(speed);
Serial2.print("\r\n");
}
}
#endif
#ifdef CD_HANDLE_RING
WiThrottle::markForBroadcast(sp->loco);
#endif
@@ -227,11 +261,8 @@ void CommandDistributor::broadcastPower() {
LCD(2,F("Power %S%S"),state=='1'?F("On"):F("Off"),reason);
}
void CommandDistributor::broadcastText(const FSH * msg) {
broadcastReply(COMMAND_TYPE, F("<I %S>\n"),msg);
#ifdef CD_HANDLE_RING
broadcastReply(WITHROTTLE_TYPE, F("Hm%S\n"), msg);
#endif
void CommandDistributor::broadcastRaw(clientType type, char * msg) {
broadcastReply(type, F("%s"),msg);
}
void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr) {

View File

@@ -2,6 +2,8 @@
* © 2022 Harald Barth
* © 2020-2021 Chris Harlow
* © 2020 Gregor Baues
* © 2022 Colin Murdoch
*
* All rights reserved.
*
* This file is part of CommandStation-EX
@@ -33,8 +35,9 @@
#endif
class CommandDistributor {
private:
public:
enum clientType: byte {NONE_TYPE,COMMAND_TYPE,WITHROTTLE_TYPE};
private:
static void broadcastToClients(clientType type);
static StringBuffer * broadcastBufferWriter;
#ifdef CD_HANDLE_RING
@@ -50,7 +53,7 @@ public :
static void setClockTime(int16_t time, int8_t rate, byte opt);
static int16_t retClockTime();
static void broadcastPower();
static void broadcastText(const FSH * msg);
static void broadcastRaw(clientType type,char * msg);
static void broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr);
template<typename... Targs> static void broadcastReply(clientType type, Targs... msg);
static void forget(byte clientId);

View File

@@ -693,7 +693,7 @@ void DCC::updateLocoReminder(int loco, byte speedCode) {
if (loco==0) {
// broadcast stop/estop but dont change direction
for (int reg = 0; reg < highestUsedReg; reg++) {
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) {

View File

@@ -152,7 +152,7 @@ byte DCCACK::getAck() {
return(0); // pending set off but not detected means no ACK.
}
#ifndef DISABLE_PROG
void DCCACK::loop() {
while (ackManagerProg) {
byte opcode=GETFLASH(ackManagerProg);
@@ -414,7 +414,7 @@ void DCCACK::callback(int value) {
(ackManagerCallback)( value);
}
}
#endif
void DCCACK::checkAck(byte sentResetsSincePacket) {
if (!ackPending) return;

View File

@@ -3,10 +3,11 @@
* © 2021 Neil McKechnie
* © 2021 Mike S
* © 2021 Herb Morton
* © 2020-2022 Harald Barth
* © 2020-2023 Harald Barth
* © 2020-2021 M Steve Todd
* © 2020-2021 Fred Decker
* © 2020-2021 Chris Harlow
* © 2022 Colin Murdoch
* All rights reserved.
*
* This file is part of CommandStation-EX
@@ -46,16 +47,14 @@
#define SENDFLASHLIST(stream,flashList) \
for (int16_t i=0;;i+=sizeof(flashList[0])) { \
int16_t value=GETHIGHFLASHW(flashList,i); \
if (value==0) break; \
StringFormatter::send(stream,F(" %d"),value); \
if (value==INT16_MAX) break; \
if (value != 0) StringFormatter::send(stream,F(" %d"),value); \
}
// These keywords are used in the <1> command. The number is what you get if you use the keyword as a parameter.
// To discover new keyword numbers , use the <$ YOURKEYWORD> command
const int16_t HASH_KEYWORD_PROG = -29718;
const int16_t HASH_KEYWORD_MAIN = 11339;
const int16_t HASH_KEYWORD_JOIN = -30750;
const int16_t HASH_KEYWORD_CABS = -11981;
const int16_t HASH_KEYWORD_RAM = 25982;
const int16_t HASH_KEYWORD_CMD = 9962;
@@ -63,7 +62,11 @@ const int16_t HASH_KEYWORD_ACK = 3113;
const int16_t HASH_KEYWORD_ON = 2657;
const int16_t HASH_KEYWORD_DCC = 6436;
const int16_t HASH_KEYWORD_SLOW = -17209;
#ifndef DISABLE_PROG
const int16_t HASH_KEYWORD_JOIN = -30750;
const int16_t HASH_KEYWORD_PROG = -29718;
const int16_t HASH_KEYWORD_PROGBOOST = -6353;
#endif
#ifndef DISABLE_EEPROM
const int16_t HASH_KEYWORD_EEPROM = -7168;
#endif
@@ -285,6 +288,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
if (direction < 0 || direction > 1)
break; // invalid direction code
if (cab > 10239 || cab < 0)
break; // beyond DCC range
DCC::setThrottle(cab, tspeed, direction);
if (params == 4) // send obsolete format T response
@@ -368,6 +373,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
return;
break;
#ifndef DISABLE_PROG
case 'w': // WRITE CV on MAIN <w CAB CV VALUE>
DCC::writeCVByteMain(p[0], p[1], p[2]);
return;
@@ -375,9 +381,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
case 'b': // WRITE CV BIT ON MAIN <b CAB CV BIT VALUE>
DCC::writeCVBitMain(p[0], p[1], p[2], p[3]);
return;
#endif
case 'M': // WRITE TRANSPARENT DCC PACKET MAIN <M REG X1 ... X9>
#ifndef DISABLE_PROG
case 'P': // WRITE TRANSPARENT DCC PACKET PROG <P REG X1 ... X9>
#endif
// NOTE: this command was parsed in HEX instead of decimal
params--; // drop REG
if (params<1) break;
@@ -392,6 +401,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
}
return;
#ifndef DISABLE_PROG
case 'W': // WRITE CV ON PROG <W CV VALUE CALLBACKNUM CALLBACKSUB>
if (!stashCallback(stream, p, ringStream))
break;
@@ -449,6 +459,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
return;
}
break;
#endif
case '1': // POWERON <1 [MAIN|PROG|JOIN]>
{
@@ -461,17 +472,19 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
prog=true;
}
if (params==1) {
if (p[0] == HASH_KEYWORD_JOIN) { // <1 JOIN>
if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN>
main=true;
}
#ifndef DISABLE_PROG
else if (p[0] == HASH_KEYWORD_JOIN) { // <1 JOIN>
main=true;
prog=true;
join=true;
}
else if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN>
main=true;
}
else if (p[0]==HASH_KEYWORD_PROG) { // <1 PROG>
prog=true;
}
#endif
else break; // will reply <X>
}
if (main) TrackManager::setMainPower(POWERMODE::ON);
@@ -495,9 +508,11 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
if (p[0]==HASH_KEYWORD_MAIN) { // <0 MAIN>
main=true;
}
#ifndef DISABLE_PROG
else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG>
prog=true;
}
#endif
else break; // will reply <X>
}
@@ -637,8 +652,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
if (params==1) {
SENDFLASHLIST(stream,RMFT2::rosterIdList)
}
else StringFormatter::send(stream,F(" %d \"%S\" \"%S\""),
id, RMFT2::getRosterName(id), RMFT2::getRosterFunctions(id));
else {
const FSH * functionNames= RMFT2::getRosterFunctions(id);
StringFormatter::send(stream,F(" %d \"%S\" \"%S\""),
id, RMFT2::getRosterName(id),
functionNames == NULL ? RMFT2::getRosterFunctions(0) : functionNames);
}
#endif
StringFormatter::send(stream, F(">\n"));
return;
@@ -892,6 +911,7 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
StringFormatter::send(stream, F("Free memory=%d\n"), DCCTimer::getMinimumFreeMemory());
break;
#ifndef DISABLE_PROG
case HASH_KEYWORD_ACK: // <D ACK ON/OFF> <D ACK [LIMIT|MIN|MAX|RETRY] Value>
if (params >= 3) {
if (p[1] == HASH_KEYWORD_LIMIT) {
@@ -912,6 +932,7 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
Diag::ACK = onOff;
}
return true;
#endif
case HASH_KEYWORD_CMD: // <D CMD ON/OFF>
Diag::CMD = onOff;
@@ -934,11 +955,11 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
Diag::LCN = onOff;
return true;
#endif
#ifndef DISABLE_PROG
case HASH_KEYWORD_PROGBOOST:
TrackManager::progTrackBoosted=true;
return true;
#endif
case HASH_KEYWORD_RESET:
DCCTimer::reset();
break; // and <X> if we didnt restart

View File

@@ -1,7 +1,7 @@
/*
* © 2022 Paul M. Antoine
* © 2022-2023 Paul M. Antoine
* © 2021 Mike S
* © 2021-2022 Harald Barth
* © 2021-2023 Harald Barth
* © 2021 Fred Decker
* All rights reserved.
*
@@ -62,6 +62,9 @@ class DCCTimer {
static bool isPWMPin(byte pin);
static void setPWM(byte pin, bool high);
static void clearPWM();
static void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency);
static void DCCEXanalogWrite(uint8_t pin, int value);
// Update low ram level. Allow for extra bytes to be specified
// by estimation or inspection, that may be used by other
// called subroutines. Must be called with interrupts disabled.

View File

@@ -150,6 +150,45 @@ int DCCTimer::freeMemory() {
void DCCTimer::reset() {
ESP.restart();
}
#include "esp32-hal.h"
#include "soc/soc_caps.h"
#ifdef SOC_LEDC_SUPPORT_HS_MODE
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM<<1)
#else
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM)
#endif
static int8_t pin_to_channel[SOC_GPIO_PIN_COUNT] = { 0 };
static int cnt_channel = LEDC_CHANNELS;
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency) {
if (pin < SOC_GPIO_PIN_COUNT) {
if (pin_to_channel[pin] != 0) {
ledcSetup(pin_to_channel[pin], frequency, 8);
}
}
}
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
if (pin < SOC_GPIO_PIN_COUNT) {
if (pin_to_channel[pin] == 0) {
if (!cnt_channel) {
log_e("No more PWM channels available! All %u already used", LEDC_CHANNELS);
return;
}
pin_to_channel[pin] = --cnt_channel;
ledcAttachPin(pin, cnt_channel);
ledcSetup(cnt_channel, 1000, 8);
} else {
ledcAttachPin(pin, pin_to_channel[pin]);
}
ledcWrite(pin_to_channel[pin], value);
}
}
int ADCee::init(uint8_t pin) {
pinMode(pin, ANALOG);
adc1_config_width(ADC_WIDTH_BIT_12);

View File

@@ -1,8 +1,8 @@
/*
* © 2023 Neil McKechnie
* © 2022 Paul M. Antoine
* © 2022-23 Paul M. Antoine
* © 2021 Mike S
* © 2021 Harald Barth
* © 2021, 2023 Harald Barth
* © 2021 Fred Decker
* © 2021 Chris Harlow
* © 2021 David Cutting
@@ -30,6 +30,10 @@
#ifdef ARDUINO_ARCH_STM32
#include "DCCTimer.h"
#ifdef DEBUG_ADC
#include "TrackManager.h"
#endif
#include "DIAG.h"
#if defined(ARDUINO_NUCLEO_F411RE)
// Nucleo-64 boards don't have Serial1 defined by default
@@ -37,17 +41,22 @@ HardwareSerial Serial1(PB7, PA15); // Rx=PB7, Tx=PA15 -- CN7 pins 17 and 21 - F
// Serial2 is defined to use USART2 by default, but is in fact used as the diag console
// via the debugger on the Nucleo-64. It is therefore unavailable for other DCC-EX uses like WiFi, DFPlayer, etc.
// Let's define Serial6 as an additional serial port (the only other option for the Nucleo-64s)
HardwareSerial Serial6(PA12, PA11); // Rx=PA12, Tx=PA11 -- CN10 pins 12 and 14 - F411RE
HardwareSerial Serial3(PA12, PA11); // Rx=PA12, Tx=PA11 -- CN10 pins 12 and 14 - F411RE
#elif defined(ARDUINO_NUCLEO_F446RE)
// Nucleo-64 boards don't have Serial1 defined by default
HardwareSerial Serial1(PA10, PB6); // Rx=PA10 (D2), Tx=PB6 (D10) -- CN10 pins 17 and 9 - F446RE
// HardwareSerial Serial1(PA10, PB6); // Rx=PA10 (D2), Tx=PB6 (D10) -- CN10 pins 17 and 9 - F446RE
// Serial2 is defined to use USART2 by default, but is in fact used as the diag console
// via the debugger on the Nucleo-64. It is therefore unavailable for other DCC-EX uses like WiFi, DFPlayer, etc.
HardwareSerial Serial1(PC11, PC10); // Rx=PC11, Tx=PC10 -- USART3 - F446RE
HardwareSerial Serial3(PD2, PC12); // Rx=PC7, Tx=PC6 -- UART5 - F446RE
// NB: USART3 and USART6 are available but as yet undefined
#elif defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)
// Nucleo-144 boards don't have Serial1 defined by default
HardwareSerial Serial1(PG9, PG14); // Rx=PG9, Tx=PG14 -- D0, D1 - F412ZG/F446ZE
HardwareSerial Serial1(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6
// Serial3 is defined to use USART3 by default, but is in fact used as the diag console
// via the debugger on the Nucleo-144. It is therefore unavailable for other DCC-EX uses like WiFi, DFPlayer, etc.
#else
#warning Serial1 not defined
#error STM32 board selected is not yet explicitly supported - so Serial1 peripheral is not defined
#endif
///////////////////////////////////////////////////////////////////////////////////////////////
@@ -227,6 +236,9 @@ void DCCTimer::reset() {
#define NUM_ADC_INPUTS NUM_ANALOG_INPUTS
// TODO: may need to use uint32_t on STMF4xx variants with > 16 analog inputs!
#if defined(ARDUINO_NUCLEO_F446RE) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)
#warning STM32 board selected not fully supported - only use ADC1 inputs 0-15 for current sensing!
#endif
uint16_t ADCee::usedpins = 0;
int * ADCee::analogvals = NULL;
uint32_t * analogchans = NULL;
@@ -299,6 +311,8 @@ int ADCee::init(uint8_t pin) {
analogchans[id] = adcchan; // Keep track of which ADC channel is used for reading this pin
usedpins |= (1 << id); // This pin is now ready
DIAG(F("ADCee::init(): value=%d, channel=%d, id=%d"), value, adcchan, id);
return value;
}
@@ -332,11 +346,13 @@ void ADCee::scan() {
// found value
analogvals[id] = ADC1->DR;
// advance at least one track
// for scope debug TrackManager::track[1]->setBrake(0);
#ifdef DEBUG_ADC
if (id == 1) TrackManager::track[1]->setBrake(0);
#endif
waiting = false;
id++;
mask = mask << 1;
if (id == NUM_ADC_INPUTS+1) {
if (mask == 0) { // the 1 has been shifted out
id = 0;
mask = 1;
}
@@ -347,18 +363,20 @@ void ADCee::scan() {
// look for a valid track to sample or until we are around
while (true) {
if (mask & usedpins) {
// start new ADC aquire on id
// start new ADC aquire on id
ADC1->SQR3 = analogchans[id]; //1st conversion in regular sequence
ADC1->CR2 |= (1 << 30); //Start 1st conversion SWSTART
// for scope debug TrackManager::track[1]->setBrake(1);
waiting = true;
return;
#ifdef DEBUG_ADC
if (id == 1) TrackManager::track[1]->setBrake(1);
#endif
waiting = true;
return;
}
id++;
mask = mask << 1;
if (id == NUM_ADC_INPUTS+1) {
id = 0;
mask = 1;
if (mask == 0) { // the 1 has been shifted out
id = 0;
mask = 1;
}
}
}

View File

@@ -1,61 +0,0 @@
/*
* © 2022 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/>.
*/
#ifdef ARDUINO_ARCH_ESP32
#include <Arduino.h>
#include "ESP32-fixes.h"
#include "esp32-hal.h"
#include "soc/soc_caps.h"
#ifdef SOC_LEDC_SUPPORT_HS_MODE
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM<<1)
#else
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM)
#endif
static int8_t pin_to_channel[SOC_GPIO_PIN_COUNT] = { 0 };
static int cnt_channel = LEDC_CHANNELS;
void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency) {
if (pin < SOC_GPIO_PIN_COUNT) {
if (pin_to_channel[pin] != 0) {
ledcSetup(pin_to_channel[pin], frequency, 8);
}
}
}
void DCCEXanalogWrite(uint8_t pin, int value) {
if (pin < SOC_GPIO_PIN_COUNT) {
if (pin_to_channel[pin] == 0) {
if (!cnt_channel) {
log_e("No more PWM channels available! All %u already used", LEDC_CHANNELS);
return;
}
pin_to_channel[pin] = --cnt_channel;
ledcAttachPin(pin, cnt_channel);
ledcSetup(cnt_channel, 1000, 8);
} else {
ledcAttachPin(pin, pin_to_channel[pin]);
}
ledcWrite(pin_to_channel[pin], value);
}
}
#endif

View File

@@ -1,26 +0,0 @@
/*
* © 2022 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/>.
*/
#ifdef ARDUINO_ARCH_ESP32
#pragma once
#include <Arduino.h>
void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency);
void DCCEXanalogWrite(uint8_t pin, int value);
#endif

View File

@@ -2,6 +2,7 @@
* © 2021 Neil McKechnie
* © 2021-2023 Harald Barth
* © 2020-2023 Chris Harlow
* © 2022 Colin Murdoch
* All rights reserved.
*
* This file is part of CommandStation-EX
@@ -265,16 +266,17 @@ void RMFT2::setTurnoutHiddenState(Turnout * t) {
char RMFT2::getRouteType(int16_t id) {
for (int16_t i=0;;i+=2) {
int16_t rid= GETHIGHFLASHW(routeIdList,i);
if (rid==INT16_MAX) break;
if (rid==id) return 'R';
if (rid==0) break;
}
for (int16_t i=0;;i+=2) {
int16_t rid= GETHIGHFLASHW(automationIdList,i);
if (rid==INT16_MAX) break;
if (rid==id) return 'A';
if (rid==0) break;
}
return 'X';
}
}
// This filter intercepts <> commands to do the following:
// - Implement RMFT specific commands/diagnostics
// - Reject/modify JMRI commands that would interfere with RMFT processing
@@ -608,6 +610,7 @@ void RMFT2::loop2() {
break;
case OPCODE_SPEED:
forward=DCC::getThrottleDirection(loco)^invert;
driveLoco(operand);
break;
@@ -702,11 +705,11 @@ void RMFT2::loop2() {
DCC::setThrottle(0,1,true); // pause all locos on the track
pausingTask=this;
break;
case OPCODE_POM:
if (loco) DCC::writeCVByteMain(loco, operand, getOperand(1));
break;
case OPCODE_POWEROFF:
TrackManager::setPower(POWERMODE::OFF);
TrackManager::setJoin(false);
@@ -881,23 +884,18 @@ void RMFT2::loop2() {
while(loopTask) loopTask->kill(F("KILLALL"));
return;
#ifndef DISABLE_PROG
case OPCODE_JOIN:
TrackManager::setPower(POWERMODE::ON);
TrackManager::setJoin(true);
CommandDistributor::broadcastPower();
break;
case OPCODE_POWERON:
TrackManager::setMainPower(POWERMODE::ON);
TrackManager::setJoin(false);
CommandDistributor::broadcastPower();
break;
case OPCODE_UNJOIN:
TrackManager::setJoin(false);
CommandDistributor::broadcastPower();
break;
case OPCODE_READ_LOCO1: // READ_LOCO is implemented as 2 separate opcodes
progtrackLocoId=LOCO_ID_WAITING; // Nothing found yet
DCC::getLocoId(readLocoCallback);
@@ -918,6 +916,13 @@ void RMFT2::loop2() {
forward=true;
invert=false;
break;
#endif
case OPCODE_POWERON:
TrackManager::setMainPower(POWERMODE::ON);
TrackManager::setJoin(false);
CommandDistributor::broadcastPower();
break;
case OPCODE_START:
{
@@ -1240,7 +1245,10 @@ void RMFT2::thrungeString(uint32_t strfar, thrunger mode, byte id) {
DCCEXParser::parseOne(&USB_SERIAL,(byte*)buffer->getString(),NULL);
break;
case thrunge_broadcast:
// TODO CommandDistributor::broadcastText(buffer->getString());
CommandDistributor::broadcastRaw(CommandDistributor::COMMAND_TYPE,buffer->getString());
break;
case thrunge_withrottle:
CommandDistributor::broadcastRaw(CommandDistributor::WITHROTTLE_TYPE,buffer->getString());
break;
case thrunge_lcd:
LCD(id,F("%s"),buffer->getString());

View File

@@ -1,6 +1,7 @@
/*
* © 2021 Neil McKechnie
* © 2020-2022 Chris Harlow
* © 2022 Colin Murdoch
* © 2023 Harald Barth
* All rights reserved.
*
@@ -44,7 +45,10 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,
OPCODE_RED,OPCODE_GREEN,OPCODE_AMBER,OPCODE_DRIVE,
OPCODE_SERVO,OPCODE_SIGNAL,OPCODE_TURNOUT,OPCODE_WAITFOR,
OPCODE_PAD,OPCODE_FOLLOW,OPCODE_CALL,OPCODE_RETURN,
OPCODE_JOIN,OPCODE_UNJOIN,OPCODE_READ_LOCO1,OPCODE_READ_LOCO2,OPCODE_POM,
#ifndef DISABLE_PROG
OPCODE_JOIN,OPCODE_UNJOIN,OPCODE_READ_LOCO1,OPCODE_READ_LOCO2,
#endif
OPCODE_POM,
OPCODE_START,OPCODE_SETLOCO,OPCODE_SENDLOCO,OPCODE_FORGET,
OPCODE_PAUSE, OPCODE_RESUME,OPCODE_POWEROFF,OPCODE_POWERON,
OPCODE_ONCLOSE, OPCODE_ONTHROW, OPCODE_SERVOTURNOUT, OPCODE_PINTURNOUT,
@@ -76,7 +80,8 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,
// Ensure thrunge_lcd is put last as there may be more than one display,
// sequentially numbered from thrunge_lcd.
enum thrunger: byte {
thrunge_print, thrunge_broadcast, thrunge_serial,thrunge_parse,
thrunge_print, thrunge_broadcast, thrunge_withrottle,
thrunge_serial,thrunge_parse,
thrunge_serial1, thrunge_serial2, thrunge_serial3,
thrunge_serial4, thrunge_serial5, thrunge_serial6,
thrunge_lcn,

View File

@@ -1,5 +1,6 @@
/*
* © 2020-2022 Chris Harlow. All rights reserved.
* © 2022 Colin Murdoch
* © 2023 Harald Barth
*
* This file is part of CommandStation-EX
@@ -100,7 +101,9 @@
#undef PAUSE
#undef PIN_TURNOUT
#undef PRINT
#ifndef DISABLE_PROG
#undef POM
#endif
#undef POWEROFF
#undef POWERON
#undef READ_LOCO
@@ -141,6 +144,7 @@
#undef VIRTUAL_SIGNAL
#undef VIRTUAL_TURNOUT
#undef WAITFOR
#undef WITHROTTLE
#undef XFOFF
#undef XFON
@@ -222,7 +226,9 @@
#define PIN_TURNOUT(id,pin,description...)
#define PRINT(msg)
#define PARSE(msg)
#ifndef DISABLE_PROG
#define POM(cv,value)
#endif
#define POWEROFF
#define POWERON
#define READ_LOCO
@@ -263,6 +269,7 @@
#define VIRTUAL_SIGNAL(id)
#define VIRTUAL_TURNOUT(id,description...)
#define WAITFOR(pin)
#define WITHROTTLE(msg)
#define XFOFF(cab,func)
#define XFON(cab,func)
#endif

View File

@@ -1,6 +1,7 @@
/*
* © 2021 Neil McKechnie
* © 2020-2022 Chris Harlow
* © 2022 Colin Murdoch
* © 2023 Harald Barth
* All rights reserved.
*
@@ -80,14 +81,14 @@ void exrailHalSetup() {
#define ROUTE(id, description) id,
const int16_t HIGHFLASH RMFT2::routeIdList[]= {
#include "myAutomation.h"
0};
INT16_MAX};
// Pass 2a create throttle automation list
#include "EXRAIL2MacroReset.h"
#undef AUTOMATION
#define AUTOMATION(id, description) id,
const int16_t HIGHFLASH RMFT2::automationIdList[]= {
#include "myAutomation.h"
0};
INT16_MAX};
// Pass 3 Create route descriptions:
#undef ROUTE
@@ -152,6 +153,8 @@ const int StringMacroTracker1=__COUNTER__;
lcdid=id;\
break;\
}
#undef WITHROTTLE
#define WITHROTTLE(msg) THRUNGE(msg,thrunge_withrottle)
void RMFT2::printMessage(uint16_t id) {
thrunger tmode;
@@ -187,7 +190,7 @@ const FSH * RMFT2::getTurnoutDescription(int16_t turnoutid) {
// Pass 6: Roster IDs (count)
#include "EXRAIL2MacroReset.h"
#undef ROSTER
#define ROSTER(cabid,name,funcmap...) +1
#define ROSTER(cabid,name,funcmap...) +(cabid <= 0 ? 0 : 1)
const byte RMFT2::rosterNameCount=0
#include "myAutomation.h"
;
@@ -198,7 +201,7 @@ const byte RMFT2::rosterNameCount=0
#define ROSTER(cabid,name,funcmap...) cabid,
const int16_t HIGHFLASH RMFT2::rosterIdList[]={
#include "myAutomation.h"
0};
INT16_MAX};
// Pass 7: Roster names getter
#include "EXRAIL2MacroReset.h"
@@ -220,7 +223,7 @@ const FSH * RMFT2::getRosterFunctions(int16_t id) {
#include "myAutomation.h"
default: break;
}
return F("");
return NULL;
}
// Pass 8 Signal definitions
@@ -324,8 +327,10 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = {
#define ONTHROW(turnout_id) OPCODE_ONTHROW,V(turnout_id),
#define ONCHANGE(sensor_id) OPCODE_ONCHANGE,V(sensor_id),
#define PAUSE OPCODE_PAUSE,0,0,
#define PIN_TURNOUT(id,pin,description...) OPCODE_PINTURNOUT,V(id),OPCODE_PAD,V(pin),
#define PIN_TURNOUT(id,pin,description...) OPCODE_PINTURNOUT,V(id),OPCODE_PAD,V(pin),
#ifndef DISABLE_PROG
#define POM(cv,value) OPCODE_POM,V(cv),OPCODE_PAD,V(value),
#endif
#define POWEROFF OPCODE_POWEROFF,0,0,
#define POWERON OPCODE_POWERON,0,0,
#define PRINT(msg) OPCODE_PRINT,V(__COUNTER__ - StringMacroTracker2),
@@ -367,6 +372,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = {
#define UNLATCH(sensor_id) OPCODE_UNLATCH,V(sensor_id),
#define VIRTUAL_SIGNAL(id)
#define VIRTUAL_TURNOUT(id,description...) OPCODE_PINTURNOUT,V(id),OPCODE_PAD,V(0),
#define WITHROTTLE(msg) PRINT(msg)
#define WAITFOR(pin) OPCODE_WAITFOR,V(pin),
#define XFOFF(cab,func) OPCODE_XFOFF,V(cab),OPCODE_PAD,V(func),
#define XFON(cab,func) OPCODE_XFON,V(cab),OPCODE_PAD,V(func),

View File

@@ -1 +1 @@
#define GITHUB_SHA "devel-202304111013Z"
#define GITHUB_SHA "devel-202306190642Z"

View File

@@ -1,8 +1,8 @@
/*
* © 2022 Paul M Antoine
* © 2022-2023 Paul M Antoine
* © 2021 Mike S
* © 2021 Fred Decker
* © 2020-2022 Harald Barth
* © 2020-2023 Harald Barth
* © 2020-2021 Chris Harlow
* All rights reserved.
*
@@ -27,19 +27,16 @@
#include "DCCTimer.h"
#include "DIAG.h"
#if defined(ARDUINO_ARCH_ESP32)
#include "ESP32-fixes.h"
#endif
bool MotorDriver::commonFaultPin=false;
volatile portreg_t shadowPORTA;
volatile portreg_t shadowPORTB;
volatile portreg_t shadowPORTC;
MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int8_t brake_pin,
byte current_pin, float sense_factor, unsigned int trip_milliamps, byte fault_pin) {
powerPin=power_pin;
MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin,
byte current_pin, float sense_factor, unsigned int trip_milliamps, int16_t fault_pin) {
const FSH * warnString = F("** WARNING **");
invertPower=power_pin < 0;
if (invertPower) {
powerPin = 0-power_pin;
@@ -95,25 +92,43 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
}
else dualSignal=false;
brakePin=brake_pin;
if (brake_pin!=UNUSED_PIN){
invertBrake=brake_pin < 0;
brakePin=invertBrake ? 0-brake_pin : brake_pin;
if (invertBrake)
brake_pin = 0-brake_pin;
if (brake_pin > MAX_PIN)
DIAG(F("%S Brake pin %d > %d"), warnString, brake_pin, MAX_PIN);
brakePin=(byte)brake_pin;
getFastPin(F("BRAKE"),brakePin,fastBrakePin);
// if brake is used for railcom cutout we need to do PORTX register trick here as well
pinMode(brakePin, OUTPUT);
setBrake(true); // start with brake on in case we hace DC stuff going on
} else {
brakePin=UNUSED_PIN;
}
else brakePin=UNUSED_PIN;
currentPin=current_pin;
if (currentPin!=UNUSED_PIN) ADCee::init(currentPin);
if (currentPin!=UNUSED_PIN) {
int ret = ADCee::init(currentPin);
if (ret < -1010) { // XXX give value a name later
DIAG(F("ADCee::init error %d, disable current pin %d"), ret, currentPin);
currentPin = UNUSED_PIN;
}
}
senseOffset=0; // value can not be obtained until waveform is activated
faultPin=fault_pin;
if (faultPin != UNUSED_PIN) {
if (fault_pin != UNUSED_PIN) {
invertFault=fault_pin < 0;
if (invertFault)
fault_pin = 0-fault_pin;
if (fault_pin > MAX_PIN)
DIAG(F("%S Fault pin %d > %d"), warnString, fault_pin, MAX_PIN);
faultPin=(byte)fault_pin;
DIAG(F("Fault pin = %d invert %d"), faultPin, invertFault);
getFastPin(F("FAULT"),faultPin, 1 /*input*/, fastFaultPin);
pinMode(faultPin, INPUT);
} else {
faultPin=UNUSED_PIN;
}
// This conversion performed at compile time so the remainder of the code never needs
@@ -135,20 +150,16 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
}
if (currentPin==UNUSED_PIN)
DIAG(F("** WARNING ** No current or short detection"));
DIAG(F("%S No current or short detection"), warnString);
else {
DIAG(F("Track %c, TripValue=%d"), trackLetter, rawCurrentTripValue);
DIAG(F("Pin %d Max %dmA (%d)"), currentPin, raw2mA(rawCurrentTripValue), rawCurrentTripValue);
// self testing diagnostic for the non-float converters... may be removed when happy
// DIAG(F("senseFactorInternal=%d raw2mA(1000)=%d mA2Raw(1000)=%d"),
// senseFactorInternal, raw2mA(1000),mA2raw(1000));
}
// prepare values for current detection
sampleDelay = 0;
lastSampleTaken = millis();
progTripValue = mA2raw(TRIP_CURRENT_PROG);
}
bool MotorDriver::isPWMCapable() {
@@ -157,6 +168,7 @@ bool MotorDriver::isPWMCapable() {
void MotorDriver::setPower(POWERMODE mode) {
if (powerMode == mode) return;
bool on=mode==POWERMODE::ON;
if (on) {
// when switching a track On, we need to check the crrentOffset with the pin OFF
@@ -215,10 +227,12 @@ int MotorDriver::getCurrentRaw(bool fromISR) {
// if (fromISR == false) DIAG(F("%c: %d"), trackLetter, current);
current = current-senseOffset; // adjust with offset
if (current<0) current=0-current;
if ((faultPin != UNUSED_PIN) && isLOW(fastFaultPin) && powerMode==POWERMODE::ON)
// current >= 0 here, we use negative current as fault pin flag
if ((faultPin != UNUSED_PIN) && powerPin) {
if (invertFault ? isHIGH(fastFaultPin) : isLOW(fastFaultPin))
return (current == 0 ? -1 : -current);
}
return current;
}
#ifdef ANALOG_READ_INTERRUPT
@@ -273,6 +287,7 @@ void MotorDriver::setDCSignal(byte speedcode) {
#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)
TCCR2B = (TCCR2B & B11111000) | B00000110; // set divisor on timer 2 to result in (approx) 122.55Hz
TCCR4B = (TCCR4B & B11111000) | B00000100; // same for timer 4 but maxcount and thus divisor differs
TCCR5B = (TCCR5B & B11111000) | B00000100; // same for timer 5 which is like timer 4
#endif
// spedcoode is a dcc speed & direction
byte tSpeed=speedcode & 0x7F; // DCC Speed with 0,1 stop and speed steps 2 to 127
@@ -286,7 +301,7 @@ void MotorDriver::setDCSignal(byte speedcode) {
f = taurustones[ (tSpeed-2)/2 ] ;
}
}
DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup
DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup
}
#endif
if (tSpeed <= 1) brake = 255;
@@ -295,7 +310,7 @@ void MotorDriver::setDCSignal(byte speedcode) {
if (invertBrake)
brake=255-brake;
#if defined(ARDUINO_ARCH_ESP32)
DCCEXanalogWrite(brakePin,brake);
DCCTimer::DCCEXanalogWrite(brakePin,brake);
#else
analogWrite(brakePin,brake);
#endif
@@ -354,63 +369,123 @@ void MotorDriver::getFastPin(const FSH* type,int pin, bool input, FASTPIN & res
}
void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) {
if (millis() - lastSampleTaken < sampleDelay) return;
lastSampleTaken = millis();
int tripValue= useProgLimit?progTripValue:getRawCurrentTripValue();
// Trackname for diag messages later
switch (powerMode) {
case POWERMODE::OFF:
sampleDelay = POWER_SAMPLE_OFF_WAIT;
if (overloadNow) {
// reset overload condition as we have just turned off power
// DIAG(F("OVERLOAD POFF OFF"));
overloadNow=false;
lastPowerChange = micros();
}
if (microsSinceLastPowerChange() > POWER_SAMPLE_ALL_GOOD) {
power_sample_overload_wait = POWER_SAMPLE_OVERLOAD_WAIT;
}
break;
case POWERMODE::ON:
// Check current
lastCurrent=getCurrentRaw();
if (lastCurrent < 0) {
// We have a fault pin condition to take care of
lastCurrent = -lastCurrent;
setPower(POWERMODE::OVERLOAD); // Turn off, decide later how fast to turn on again
if (commonFaultPin) {
if (lastCurrent < tripValue) {
setPower(POWERMODE::ON); // maybe other track
}
// Write this after the fact as we want to turn on as fast as possible
// because we don't know which output actually triggered the fault pin
DIAG(F("COMMON FAULT PIN ACTIVE: POWERTOGGLE TRACK %c"), trackno + 'A');
} else {
DIAG(F("TRACK %c FAULT PIN ACTIVE - OVERLOAD"), trackno + 'A');
if (lastCurrent < tripValue) {
lastCurrent = tripValue; // exaggerate
}
// We have a fault pin condition to take care of
if (!overloadNow) {
// turn on overload condition as fault pin has gone active
// DIAG(F("OVERLOAD FPIN ON"));
overloadNow=true;
lastPowerChange = micros();
}
lastCurrent = -lastCurrent;
if (commonFaultPin) {
if (lastCurrent < tripValue) {
// probably other track, do a fast toggle.
setPower(POWERMODE::OVERLOAD); // Turn off, decide later how fast to turn on again
setPower(POWERMODE::ON); // maybe other track
// Write this after the fact as we want to turn on as fast as possible
// because we don't know which output actually triggered the fault pin
DIAG(F("COMMON FAULT PIN ACTIVE: POWERTOGGLE TRACK %c"), trackno + 'A');
}
} else {
if (lastCurrent < tripValue) {
if (power_sample_overload_wait <= (POWER_SAMPLE_OVERLOAD_WAIT * 10) && // almost virgin
microsSinceLastPowerChange() < POWER_SAMPLE_IGNORE_FAULT_LOW) {
// Ignore 50ms fault pin if no current
DIAG(F("TRACK %c FAULT PIN 50ms ignore"), trackno + 'A');
break;
}
lastCurrent = tripValue; // exaggerate so condition below (*) is true
} else {
if (power_sample_overload_wait <= POWER_SAMPLE_OVERLOAD_WAIT && // virgin
microsSinceLastPowerChange() < POWER_SAMPLE_IGNORE_FAULT_HIGH) {
// Ignore 5ms fault pin if we see current
DIAG(F("TRACK %c FAULT PIN 5ms ignore"), trackno + 'A');
break;
}
}
DIAG(F("TRACK %c FAULT PIN ACTIVE"), trackno + 'A');
}
}
if (lastCurrent < tripValue) {
sampleDelay = POWER_SAMPLE_ON_WAIT;
if(power_good_counter<100)
power_good_counter++;
else
if (power_sample_overload_wait>POWER_SAMPLE_OVERLOAD_WAIT) power_sample_overload_wait=POWER_SAMPLE_OVERLOAD_WAIT;
// // //
// above we looked at fault pin, below we look at current
// // //
if (lastCurrent < tripValue) { // see above (*)
if (overloadNow) {
// current is below trip value, turn off overload condition
// DIAG(F("OVERLOAD PON OFF"));
overloadNow=false;
lastPowerChange = micros();
}
if (microsSinceLastPowerChange() > POWER_SAMPLE_ALL_GOOD) {
power_sample_overload_wait = POWER_SAMPLE_OVERLOAD_WAIT;
}
} else {
setPower(POWERMODE::OVERLOAD);
unsigned int mA=raw2mA(lastCurrent);
unsigned int maxmA=raw2mA(tripValue);
power_good_counter=0;
sampleDelay = power_sample_overload_wait;
DIAG(F("TRACK %c POWER OVERLOAD %dmA (limit %dmA) shutdown for %dms"), trackno + 'A', mA, maxmA, sampleDelay);
if (power_sample_overload_wait >= 10000)
power_sample_overload_wait = 10000;
else
power_sample_overload_wait *= 2;
// too much current
if (!overloadNow) {
// current is over trip value, turn on overload condition
// DIAG(F("OVERLOAD PON ON"));
overloadNow=true;
lastPowerChange = micros();
}
unsigned long uSecs = microsSinceLastPowerChange();
if (power_sample_overload_wait > POWER_SAMPLE_OVERLOAD_WAIT || // not virgin
uSecs > POWER_SAMPLE_OFF_DELAY) {
// Overload has existed longer than delay (typ. 10ms)
setPower(POWERMODE::OVERLOAD);
if (overloadNow) {
// the setPower just turned off, so overload is now gone
// DIAG(F("OVERLOAD PON OFF"));
overloadNow=false;
lastPowerChange = micros();
}
unsigned int mA=raw2mA(lastCurrent);
unsigned int maxmA=raw2mA(tripValue);
DIAG(F("TRACK %c POWER OVERLOAD %dmA (limit %dmA) shutdown after %lus for %lus"),
trackno + 'A', mA, maxmA, uSecs, power_sample_overload_wait);
}
}
break;
case POWERMODE::OVERLOAD:
// Try setting it back on after the OVERLOAD_WAIT
case POWERMODE::OVERLOAD:
if (overloadNow) {
// state overload mode means power is off, turn off overload condition flag as well
// DIAG(F("OVERLOAD POVER OFF"));
overloadNow=false;
lastPowerChange = micros();
}
// Try setting it back on after the OVERLOAD_WAIT
if (microsSinceLastPowerChange() > power_sample_overload_wait) {
// adjust next wait time
power_sample_overload_wait *= 2;
if (power_sample_overload_wait > POWER_SAMPLE_RETRY_MAX)
power_sample_overload_wait = POWER_SAMPLE_RETRY_MAX;
// power on test
setPower(POWERMODE::ON);
sampleDelay = POWER_SAMPLE_ON_WAIT;
// Debug code....
DIAG(F("TRACK %c POWER RESTORE (check %dms)"), trackno + 'A', sampleDelay);
break;
default:
sampleDelay = 999; // cant get here..meaningless statement to avoid compiler warning.
// here we change power but not the overloadNow as that was
// already changed to false when we entered POWERMODE::OVERLOAD
// so we need to set the lastPowerChange anyway.
lastPowerChange = micros();
DIAG(F("TRACK %c POWER RESTORE (was off %lus)"), trackno + 'A', power_sample_overload_wait);
}
break;
default:
break;
}
}

View File

@@ -74,8 +74,9 @@
// Virtualised Motor shield 1-track hardware Interface
#ifndef UNUSED_PIN // sync define with the one in MotorDrivers.h
#define UNUSED_PIN 127 // inside int8_t
#define UNUSED_PIN 255 // inside uint8_t
#endif
#define MAX_PIN 254
class pinpair {
public:
@@ -111,8 +112,8 @@ enum class POWERMODE : byte { OFF, ON, OVERLOAD };
class MotorDriver {
public:
MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int8_t brake_pin,
byte current_pin, float senseFactor, unsigned int tripMilliamps, byte faultPin);
MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin,
byte current_pin, float senseFactor, unsigned int tripMilliamps, int16_t fault_pin);
void setPower( POWERMODE mode);
POWERMODE getPower() { return powerMode;}
// as the port registers can be shadowed to get syncronized DCC signals
@@ -185,6 +186,16 @@ class MotorDriver {
inline void setTrackLetter(char c) {
trackLetter = c;
};
// this returns how much time has passed since the last power change. If it
// was really long ago (approx > 52min) advance counter approx 35 min so that
// we are at 18 minutes again. Times for 32 bit unsigned long.
inline unsigned long microsSinceLastPowerChange() {
unsigned long now = micros();
unsigned long diff = now - lastPowerChange;
if (diff > (1UL << (7 *sizeof(unsigned long)))) // 2^(4*7)us = 268.4 seconds
lastPowerChange = now - 30000000UL; // 30 seconds ago
return diff;
};
#ifdef ANALOG_READ_INTERRUPT
bool sampleCurrentFromHW();
void startCurrentFromHW();
@@ -202,6 +213,7 @@ class MotorDriver {
bool dualSignal; // true to use signalPin2
bool invertBrake; // brake pin passed as negative means pin is inverted
bool invertPower; // power pin passed as negative means pin is inverted
bool invertFault; // fault pin passed as negative means pin is inverted
// Raw to milliamp conversion factors avoiding float data types.
// Milliamps=rawADCreading * sensefactorInternal / senseScale
@@ -215,8 +227,8 @@ class MotorDriver {
int rawCurrentTripValue;
// current sampling
POWERMODE powerMode;
unsigned long lastSampleTaken;
unsigned int sampleDelay;
bool overloadNow = false;
unsigned long lastPowerChange; // timestamp in microseconds
int progTripValue;
int lastCurrent;
#ifdef ANALOG_READ_INTERRUPT
@@ -226,10 +238,19 @@ class MotorDriver {
int maxmA;
int tripmA;
// Wait times for power management. Unit: milliseconds
static const int POWER_SAMPLE_ON_WAIT = 100;
static const int POWER_SAMPLE_OFF_WAIT = 1000;
static const int POWER_SAMPLE_OVERLOAD_WAIT = 20;
// Times for overload management. Unit: microseconds.
// Base for wait time until power is turned on again
static const unsigned long POWER_SAMPLE_OVERLOAD_WAIT = 100UL;
// Time after we consider all faults old and forgotten
static const unsigned long POWER_SAMPLE_ALL_GOOD = 5000000UL;
// How long to ignore fault pin if current is under limit
static const unsigned long POWER_SAMPLE_IGNORE_FAULT_LOW = 50000UL;
// How long to ignore fault pin if current is higher than limit
static const unsigned long POWER_SAMPLE_IGNORE_FAULT_HIGH = 5000UL;
// How long to wait between overcurrent and turning off
static const unsigned long POWER_SAMPLE_OFF_DELAY = 10000UL;
// Upper limit for retry period
static const unsigned long POWER_SAMPLE_RETRY_MAX = 10000000UL;
// Trip current for programming track, 250mA. Change only if you really
// need to be non-NMRA-compliant because of decoders that are not either.

View File

@@ -1,7 +1,7 @@
/*
* © 2022 Paul M. Antoine
* © 2022-2023 Paul M. Antoine
* © 2021 Fred Decker
* © 2020-2022 Harald Barth
* © 2020-2023 Harald Barth
* (c) 2020 Chris Harlow. All rights reserved.
* (c) 2021 Fred Decker. All rights reserved.
* (c) 2020 Harald Barth. All rights reserved.
@@ -36,7 +36,7 @@
// custom defines in config.h.
#ifndef UNUSED_PIN // sync define with the one in MotorDriver.h
#define UNUSED_PIN 127 // inside int8_t
#define UNUSED_PIN 255 // inside uint8_t
#endif
// The MotorDriver definition is:
@@ -60,7 +60,8 @@
// Arduino STANDARD Motor Shield, used on different architectures:
#if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32)
// Setup for SAMD21 Sparkfun DEV board using Arduino standard Motor Shield R3 (MUST be R3
// Standard Motor Shield definition for 3v3 processors (other than the ESP32)
// Setup for SAMD21 Sparkfun DEV board MUST use Arduino Motor Shield R3 (MUST be R3
// for 3v3 compatibility!!) senseFactor for 3.3v systems is 1.95 as calculated when using
// 10-bit A/D samples, and for 12-bit samples it's more like 0.488, but we probably need
// to tweak both these
@@ -70,15 +71,27 @@
#define SAMD_STANDARD_MOTOR_SHIELD STANDARD_MOTOR_SHIELD
#define STM32_STANDARD_MOTOR_SHIELD STANDARD_MOTOR_SHIELD
// EX 8874 based shield connected to a 3V3 system with 12-bit (4096) ADC
#define EX8874_SHIELD F("EX8874"), \
new MotorDriver( 3, 12, UNUSED_PIN, 9, A0, 1.27, 5000, A4), \
new MotorDriver(11, 13, UNUSED_PIN, 8, A1, 1.27, 5000, A5)
#elif defined(ARDUINO_ARCH_ESP32)
// STANDARD shield on an ESPDUINO-32 (ESP32 in Uno form factor). The shield must be eiter the
// 3.3V compatible R3 version or it has to be modified to not supply more than 3.3V to the
// analog inputs. Here we use analog inputs A2 and A3 as A0 and A1 are wired in a way so that
// they are not useable at the same time as WiFi (what a bummer). The numbers below are the
// actual GPIO numbers. In comments the numbers the pins have on an Uno.
#define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"), \
new MotorDriver(25/* 3*/, 19/*12*/, UNUSED_PIN, 13/*9*/, 35/*A2*/, 0.70, 1500, UNUSED_PIN), \
new MotorDriver(23/*11*/, 18/*13*/, UNUSED_PIN, 12/*8*/, 34/*A3*/, 0.70, 1500, UNUSED_PIN)
#define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"), \
new MotorDriver(25/* 3*/, 19/*12*/, UNUSED_PIN, 13/*9*/, 35/*A2*/, 0.70, 1500, UNUSED_PIN), \
new MotorDriver(23/*11*/, 18/*13*/, UNUSED_PIN, 12/*8*/, 34/*A3*/, 0.70, 1500, UNUSED_PIN)
// EX 8874 based shield connected to a 3.3V system (like ESP32) and 12bit (4096) ADC
// numbers are GPIO numbers. comments are UNO form factor shield pin numbers
#define EX8874_SHIELD F("EX8874"),\
new MotorDriver(25/* 3*/, 19/*12*/, UNUSED_PIN, 13/*9*/, 35/*A2*/, 1.27, 5000, 36 /*A4*/), \
new MotorDriver(23/*11*/, 18/*13*/, UNUSED_PIN, 12/*8*/, 34/*A3*/, 1.27, 5000, 39 /*A5*/)
#else
// STANDARD shield on any Arduino Uno or Mega compatible with the original specification.
@@ -88,6 +101,12 @@
#define BRAKE_PWM_SWAPPED_MOTOR_SHIELD F("BPS_MOTOR_SHIELD"), \
new MotorDriver(-9 , 12, UNUSED_PIN, -3, A0, 2.99, 1500, UNUSED_PIN), \
new MotorDriver(-8 , 13, UNUSED_PIN,-11, A1, 2.99, 1500, UNUSED_PIN)
// EX 8874 based shield connected to a 5V system (like Arduino) and 10bit (1024) ADC
#define EX8874_SHIELD F("EX8874"), \
new MotorDriver( 3, 12, UNUSED_PIN, 9, A0, 5.08, 5000, A4), \
new MotorDriver(11, 13, UNUSED_PIN, 8, A1, 5.08, 5000, A5)
#endif
// Pololu Motor Shield

View File

@@ -87,6 +87,9 @@ void SerialManager::init() {
delay(1000);
}
#endif
#ifdef SABERTOOTH
Serial2.begin(9600, SERIAL_8N1, 16, 17); // GPIO 16 RXD2; GPIO 17 TXD2 on ESP32
#endif
}
void SerialManager::broadcast(char * stringBuffer) {

View File

@@ -33,8 +33,9 @@
FOR_EACH_TRACK(t) \
if (trackMode[t]==findmode) \
track[t]->function;
#ifndef DISABLE_PROG
const int16_t HASH_KEYWORD_PROG = -29718;
#endif
const int16_t HASH_KEYWORD_MAIN = 11339;
const int16_t HASH_KEYWORD_OFF = 22479;
const int16_t HASH_KEYWORD_DC = 2183;
@@ -116,7 +117,11 @@ void TrackManager::Setup(const FSH * shieldname,
// Default the first 2 tracks (which may be null) and perform HA waveform check.
setTrackMode(0,TRACK_MODE_MAIN);
#ifndef DISABLE_PROG
setTrackMode(1,TRACK_MODE_PROG);
#else
setTrackMode(1,TRACK_MODE_MAIN);
#endif
// TODO Fault pin config for odd motor boards (example pololu)
// MotorDriver::commonFaultPin = ((mainDriver->getFaultPin() == progDriver->getFaultPin())
@@ -198,7 +203,11 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
pinMode(p.invpin, OUTPUT); // gpio_reset_pin may reset to input
}
#endif
#ifndef DISABLE_PROG
if (mode==TRACK_MODE_PROG) {
#else
if (false) {
#endif
// only allow 1 track to be prog
FOR_EACH_TRACK(t)
if (trackMode[t]==TRACK_MODE_PROG && t != trackToSet) {
@@ -306,8 +315,10 @@ bool TrackManager::parseJ(Print *stream, int16_t params, int16_t p[])
if (params==2 && p[1]==HASH_KEYWORD_MAIN) // <= id MAIN>
return setTrackMode(p[0],TRACK_MODE_MAIN);
#ifndef DISABLE_PROG
if (params==2 && p[1]==HASH_KEYWORD_PROG) // <= id PROG>
return setTrackMode(p[0],TRACK_MODE_PROG);
#endif
if (params==2 && p[1]==HASH_KEYWORD_OFF) // <= id OFF>
return setTrackMode(p[0],TRACK_MODE_OFF);
@@ -332,9 +343,11 @@ void TrackManager::streamTrackState(Print* stream, byte t) {
case TRACK_MODE_MAIN:
format=F("<= %c MAIN>\n");
break;
#ifndef DISABLE_PROG
case TRACK_MODE_PROG:
format=F("<= %c PROG>\n");
break;
#endif
case TRACK_MODE_OFF:
format=F("<= %c OFF>\n");
break;
@@ -357,8 +370,10 @@ void TrackManager::streamTrackState(Print* stream, byte t) {
byte TrackManager::nextCycleTrack=MAX_TRACKS;
void TrackManager::loop() {
DCCWaveform::loop();
DCCACK::loop();
DCCWaveform::loop();
#ifndef DISABLE_PROG
DCCACK::loop();
#endif
bool dontLimitProg=DCCACK::isActive() || progTrackSyncMain || progTrackBoosted;
nextCycleTrack++;
if (nextCycleTrack>lastTrack) nextCycleTrack=0;

View File

@@ -84,8 +84,15 @@ class TrackManager {
static int16_t joinRelay;
static bool progTrackSyncMain; // true when prog track is a siding switched to main
static bool progTrackBoosted; // true when prog track is not current limited
static bool progTrackBoosted; // true when prog track is not current limited
#ifdef DEBUG_ADC
public:
#else
private:
#endif
static MotorDriver* track[MAX_TRACKS];
private:
static void addTrack(byte t, MotorDriver* driver);
static byte lastTrack;
@@ -93,7 +100,6 @@ class TrackManager {
static POWERMODE mainPowerGuess;
static void applyDCSpeed(byte t);
static MotorDriver* track[MAX_TRACKS];
static TRACK_MODE trackMode[MAX_TRACKS];
static int16_t trackDCAddr[MAX_TRACKS]; // dc address if TRACK_MODE_DC or TRACK_MODE_DCX
#ifdef ARDUINO_ARCH_ESP32

View File

@@ -250,6 +250,7 @@
}
}
tt = (Turnout *)new ServoTurnout(id, vpin, thrownPosition, closedPosition, profile, closed);
DIAG(F("Turnout 0x%x size %d size %d"), tt, sizeof(Turnout),sizeof(struct TurnoutData));
IODevice::writeAnalogue(vpin, closed ? closedPosition : thrownPosition, PCA9685::Instant);
return tt;
#else

View File

@@ -69,10 +69,12 @@ protected:
uint16_t id;
} _turnoutData; // 3 bytes
#ifndef DISABLE_EEPROM
// Address in eeprom of first byte of the _turnoutData struct (containing the closed flag).
// Set to zero if the object has not been saved in EEPROM, e.g. for newly created Turnouts, and
// for all LCN turnouts.
uint16_t _eepromAddress = 0;
#endif
// Pointer to next turnout on linked list.
Turnout *_nextTurnout = 0;

View File

@@ -235,6 +235,10 @@ int WiThrottle::getLocoId(byte * cmd) {
void WiThrottle::multithrottle(RingStream * stream, byte * cmd){
char throttleChar=cmd[1];
int locoid=getLocoId(cmd+3); // -1 for *
if (locoid > 10239 || locoid < -1) {
StringFormatter::send(stream, F("No valid DCC loco %d\n"), locoid);
return;
}
byte * aval=cmd;
while(*aval !=';' && *aval !='\0') aval++;
if (*aval) aval+=2; // skip ;>
@@ -527,10 +531,13 @@ void WiThrottle::sendRoster(Print* stream) {
rosterSent=true;
#ifdef EXRAIL_ACTIVE
StringFormatter::send(stream,F("RL%d"), RMFT2::rosterNameCount);
for (int16_t r=0;r<RMFT2::rosterNameCount;r++) {
for (int16_t r=0;;r++) {
int16_t cabid=GETHIGHFLASHW(RMFT2::rosterIdList,r*2);
StringFormatter::send(stream,F("]\\[%S}|{%d}|{%c"),
RMFT2::getRosterName(cabid),cabid,cabid<128?'S':'L');
if (cabid == INT16_MAX)
break;
if (cabid > 0)
StringFormatter::send(stream,F("]\\[%S}|{%d}|{%c"),
RMFT2::getRosterName(cabid),cabid,cabid<128?'S':'L');
}
StringFormatter::send(stream,F("\n"));
#else
@@ -544,14 +551,14 @@ void WiThrottle::sendRoutes(Print* stream) {
// first pass automations
for (int ix=0;;ix+=2) {
int16_t id =GETHIGHFLASHW(RMFT2::automationIdList,ix);
if (id==0) break;
if (id==INT16_MAX) break;
const FSH * desc=RMFT2::getRouteDescription(id);
StringFormatter::send(stream,F("]\\[A%d}|{%S}|{4"),id,desc);
}
// second pass routes.
for (int ix=0;;ix+=2) {
int16_t id=GETHIGHFLASHW(RMFT2::routeIdList,ix);
if (id==0) break;
if (id==INT16_MAX) break;
const FSH * desc=RMFT2::getRouteDescription(id);
StringFormatter::send(stream,F("]\\[R%d}|{%S}|{2"),id,desc);
}
@@ -567,9 +574,13 @@ void WiThrottle::sendFunctions(Print* stream, byte loco) {
myLocos[loco].functionToggles=1<<2; // F2 (HORN) is a non-toggle
#ifdef EXRAIL_ACTIVE
const char * functionNames=(char *) RMFT2::getRosterFunctions(locoid);
if (!functionNames) {
// no roster, use non-exrail presets as above
const FSH * functionNames= RMFT2::getRosterFunctions(locoid);
if (functionNames == NULL) {
// no roster entry for locoid, try to find default entry
functionNames= RMFT2::getRosterFunctions(0);
}
if (functionNames == NULL) {
// no default roster entry either, use non-exrail presets as above
}
else if (GETFLASH(functionNames)=='\0') {
// "" = Roster but no functions given
@@ -584,7 +595,7 @@ void WiThrottle::sendFunctions(Print* stream, byte loco) {
fkeys=0;
bool firstchar=true;
for (int fx=0;;fx++) {
char c=GETFLASH(functionNames+fx);
char c=GETFLASH((char *)functionNames+fx);
if (c=='\0') {
fkeys++;
break;

View File

@@ -58,6 +58,14 @@ Stream * WifiInterface::wifiStream;
#define NUM_SERIAL 1
#endif
// For STM32 we need to define Serial3 in the platform specific
// DCCTimerSTM32.cpp file, we here make the assumption that it
// exists to link against.
#ifdef ARDUINO_ARCH_STM32
#if NUM_SERIAL > 2
extern HardwareSerial Serial3;
#endif
#endif
bool WifiInterface::setup(long serial_link_speed,
const FSH *wifiESSID,
const FSH *wifiPassword,
@@ -83,6 +91,8 @@ bool WifiInterface::setup(long serial_link_speed,
#endif
// Other serials are tried, depending on hardware.
// Currently only the Arduino Mega 2560 has usable Serial2
#if defined(ARDUINO_AVR_MEGA2560)
#if NUM_SERIAL > 1 && !defined(SERIAL2_COMMANDS)
if (wifiUp == WIFI_NOAT)
{
@@ -90,7 +100,10 @@ bool WifiInterface::setup(long serial_link_speed,
wifiUp = setup(Serial2, wifiESSID, wifiPassword, hostname, port, channel);
}
#endif
#endif
// We guess here that in all architctures that have a Serial3
// we can use it for our purpose.
#if NUM_SERIAL > 2 && !defined(SERIAL3_COMMANDS)
if (wifiUp == WIFI_NOAT)
{

View File

@@ -1,7 +1,7 @@
/*
* © 2022 Paul M. Antoine
* © 2021 Neil McKechnie
* © 2020-2021 Harald Barth
* © 2020-2023 Harald Barth
* © 2020-2021 Fred Decker
* © 2020-2021 Chris Harlow
*
@@ -27,6 +27,16 @@ The configuration file for DCC-EX Command Station
**********************************************************************/
/////////////////////////////////////////////////////////////////////////////////////
// If you want to add your own motor driver definition(s), add them here
// For example MY_SHIELD with display name "MINE":
// (remove comment start and end marker if you want to edit and use that)
/*
#define MY_SHIELD F("MINE"), \
new MotorDriver( 3, 12, UNUSED_PIN, 9, A0, 5.08, 3000, A4), \
new MotorDriver(11, 13, UNUSED_PIN, 8, A1, 5.08, 1500, A5)
*/
/////////////////////////////////////////////////////////////////////////////////////
// NOTE: Before connecting these boards and selecting one in this software
// check the quick install guides!!! Some of these boards require a voltage
@@ -34,15 +44,15 @@ The configuration file for DCC-EX Command Station
// the correct resistor could damage the sense pin on your Arduino or destroy
// the device.
//
// DEFINE MOTOR_SHIELD_TYPE BELOW ACCORDING TO THE FOLLOWING TABLE:
// DEFINE MOTOR_SHIELD_TYPE BELOW. THESE ARE EXAMPLES. FULL LIST IN MotorDrivers.h
//
// STANDARD_MOTOR_SHIELD : Arduino Motor shield Rev3 based on the L298 with 18V 2A per channel
// POLOLU_MOTOR_SHIELD : Pololu MC33926 Motor Driver (not recommended for prog track)
// POLOLU_TB9051FTG : Pololu Dual TB9051FTG Motor Driver
// FUNDUMOTO_SHIELD : Fundumoto Shield, no current sensing (not recommended, no short protection)
// FIREBOX_MK1 : The Firebox MK1
// FIREBOX_MK1S : The Firebox MK1S
// IBT_2_WITH_ARDUINO : Arduino Motor Shield for PROG and IBT-2 for MAIN
// EX8874_SHIELD : DCC-EX TI DRV8874 based motor shield
// |
// +-----------------------v
//
@@ -128,7 +138,7 @@ The configuration file for DCC-EX Command Station
//OR define OLED_DRIVER width,height[,address] in pixels (address auto detected if not supplied)
// 128x32 or 128x64 I2C SSD1306-based devices are supported.
// Use 132,64 for a SH1106-based I2C device with a 128x64 display.
// #define OLED_DRIVER 128,32,0x3c
// #define OLED_DRIVER 0x3c,128,32
// Define scroll mode as 0, 1 or 2
// * #define SCROLLMODE 0 is scroll continuous (fill screen if poss),
@@ -141,7 +151,7 @@ The configuration file for DCC-EX Command Station
//
// If you do not need the EEPROM at all, you can disable all the code that saves
// data in the EEPROM. You might want to do that if you are in a Arduino UNO
// and want to use the EX-RAIL automation. Otherwise you do not have enough RAM
// and want to use the EXRAIL automation. Otherwise you do not have enough RAM
// to do that. Of course, then none of the EEPROM related commands work.
//
// EEPROM does not work on ESP32. So on ESP32, EEPROM will always be disabled,
@@ -149,6 +159,17 @@ The configuration file for DCC-EX Command Station
//
// #define DISABLE_EEPROM
/////////////////////////////////////////////////////////////////////////////////////
// DISABLE PROG
//
// If you do not need programming capability, you can disable all programming related
// commands. You might want to do that if you are using an Arduino UNO and still want
// to use EXRAIL automation, as the Uno is lacking in RAM and Flash to run both.
//
// Note this disables all programming functionality, including EXRAIL.
//
// #define DISABLE_PROG
/////////////////////////////////////////////////////////////////////////////////////
// REDEFINE WHERE SHORT/LONG ADDR break is. According to NMRA the last short address
// is 127 and the first long address is 128. There are manufacturers which have
@@ -224,5 +245,15 @@ The configuration file for DCC-EX Command Station
//
//#define SERIAL_BT_COMMANDS
// SABERTOOTH
//
// This is a very special option and only useful if you happen to have a
// sabertooth motor controller from dimension engineering configured to
// take commands from and ESP32 via serial at 9600 baud from GPIO17 (TX)
// and GPIO16 (RX, currently unused).
// The number defined is the DCC address for which speed controls are sent
// to the sabertooth controller _as_well_. Default: Undefined.
//
//#define SABERTOOTH 1
/////////////////////////////////////////////////////////////////////////////////////

View File

@@ -1,169 +0,0 @@
/**********************************************************************
Config.h
COPYRIGHT (c) 2013-2016 Gregg E. Berman
COPYRIGHT (c) 2020 Fred Decker
The configuration file for DCC++ EX Command Station
**********************************************************************/
/////////////////////////////////////////////////////////////////////////////////////
// NOTE: Before connecting these boards and selecting one in this software
// check the quick install guides!!! Some of these boards require a voltage
// generating resitor on the current sense pin of the device. Failure to select
// the correct resistor could damage the sense pin on your Arduino or destroy
// the device.
//
// DEFINE MOTOR_SHIELD_TYPE BELOW ACCORDING TO THE FOLLOWING TABLE:
//
// STANDARD_MOTOR_SHIELD : Arduino Motor shield Rev3 based on the L298 with 18V 2A per channel
// POLOLU_MOTOR_SHIELD : Pololu MC33926 Motor Driver (not recommended for prog track)
// FUNDUMOTO_SHIELD : Fundumoto Shield, no current sensing (not recommended, no short protection)
// FIREBOX_MK1 : The Firebox MK1
// FIREBOX_MK1S : The Firebox MK1S
// |
// +-----------------------v
//
// #define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"),
// new MotorDriver(3, 12, UNUSED_PIN, 9, A0, 0.488, 1500, UNUSED_PIN),
// new MotorDriver(11, 13, UNUSED_PIN, 8, A1, 0.488, 1500, UNUSED_PIN)
#define MOTOR_SHIELD_TYPE STANDARD_MOTOR_SHIELD
/////////////////////////////////////////////////////////////////////////////////////
//
// The IP port to talk to a WIFI or Ethernet shield.
//
#define IP_PORT 2560
/////////////////////////////////////////////////////////////////////////////////////
//
// NOTE: Only supported on Arduino Mega
// Set to false if you not even want it on the Arduino Mega
//
//#define ENABLE_WIFI true
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE WiFi Parameters (only in effect if WIFI is on)
//
// If DONT_TOUCH_WIFI_CONF is set, all WIFI config will be done with
// the <+> commands and this sketch will not change anything over
// AT commands and the other WIFI_* defines below do not have any effect.
//#define DONT_TOUCH_WIFI_CONF
//
// WIFI_SSID is the network name IF you want to use your existing home network.
// Do NOT change this if you want to use the WiFi in Access Point (AP) mode.
//
// If you do NOT set the WIFI_SSID, the WiFi chip will first try
// to connect to the previously configured network and if that fails
// fall back to Access Point mode. The SSID of the AP will be
// automatically set to DCCEX_*.
//
// Your SSID may not conain ``"'' (double quote, ASCII 0x22).
#define WIFI_SSID "Your network name"
//
// WIFI_PASSWORD is the network password for your home network or if
// you want to change the password from default AP mode password
// to the AP password you want.
// Your password may not conain ``"'' (double quote, ASCII 0x22).
#define WIFI_PASSWORD "deadcafe"
//
// WIFI_HOSTNAME: You probably don't need to change this
#define WIFI_HOSTNAME "dccex"
//
/////////////////////////////////////////////////////////////////////////////////////
//
// Wifi connect timeout in milliseconds. Default is 14000 (14 seconds). You only need
// to set this if you have an extremely slow Wifi router.
//
#define WIFI_CONNECT_TIMEOUT 14000
/////////////////////////////////////////////////////////////////////////////////////
//
// ENABLE_ETHERNET: Set to true if you have an Arduino Ethernet card (wired). This
// is not for Wifi. You will then need the Arduino Ethernet library as well
//
//#define ENABLE_ETHERNET true
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE STATIC IP ADDRESS *OR* COMMENT OUT TO USE DHCP
//
//#define IP_ADDRESS { 192, 168, 1, 31 }
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE MAC ADDRESS ARRAY FOR ETHERNET COMMUNICATIONS INTERFACE
//
// Uncomment to use with Ethernet Shields
//
// Ethernet Shields do not have have a MAC address in hardware. There may be one on
// a sticker on the Shield that you should use. Otherwise choose one of the ones below
// Be certain that no other device on your network has this same MAC address!
//
// 52:b8:8a:8e:ce:21
// e3:e9:73:e1:db:0d
// 54:2b:13:52:ac:0c
// NOTE: This is not used with ESP8266 WiFi modules.
//#define MAC_ADDRESS { 0x52, 0xB8, 0x8A, 0x8E, 0xCE, 0x21 } // MAC address of your networking card found on the sticker on your card or take one from above
//
// #define MAC_ADDRESS { 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xEF }
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE LCD SCREEN USAGE BY THE BASE STATION
//
// Note: This feature requires an I2C enabled LCD screen using a Hitachi HD44780
// controller and a PCF8574 based I2C 'backpack',
// OR an I2C Oled screen based on SSD1306 (128x64 or 128x32) controller,
// OR an I2C Oled screen based on SH1106 (132x64) controller.
// To enable, uncomment one of the lines below
// define LCD_DRIVER for I2C LCD address 0x3f,16 cols, 2 rows
//#define LCD_DRIVER {SubBus_4,0x27},20,4
//OR define OLED_DRIVER width,height in pixels (address auto detected)
#if defined(ARDUINO_ARCH_STM32)
#define OLED_DRIVER 0x3c, 128, 64
#else
#define OLED_DRIVER {SubBus_0,0x3c}, 128, 32
#endif
#define SCROLLMODE 1
/////////////////////////////////////////////////////////////////////////////////////
// DISABLE EEPROM
//
// If you do not need the EEPROM at all, you can disable all the code that saves
// data in the EEPROM. You might want to do that if you are in a Arduino UNO
// and want to use the EX-RAIL automation. Otherwise you do not have enough RAM
// to do that. Of course, then none of the EEPROM related commands work.
//
#define DISABLE_EEPROM
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE TURNOUTS/ACCESSORIES FOLLOW NORM RCN-213
//
// According to norm RCN-213 a DCC packet with a 1 is closed/straight
// and one with a 0 is thrown/diverging. In DCC++ Classic, and in previous
// versions of DCC++EX, a turnout throw command was implemented in the packet as
// '1' and a close command as '0'. The #define below makes the states
// match with the norm. But we don't want to cause havoc on existent layouts,
// so we define this only for new installations. If you don't want this,
// don't add it to your config.h.
//#define DCC_TURNOUTS_RCN_213
// The following #define likewise inverts the behaviour of the <a> command
// for triggering DCC Accessory Decoders, so that <a addr subaddr 0> generates a
// DCC packet with D=1 (close turnout) and <a addr subaddr 1> generates D=0
// (throw turnout).
//#define DCC_ACCESSORY_RCN_213
/////////////////////////////////////////////////////////////////////////////////////

View File

@@ -147,7 +147,8 @@
#ifndef I2C_USE_WIRE
#define I2C_USE_WIRE
#endif
#undef NUM_SERIAL
#define NUM_SERIAL 3
/* TODO when ready
#elif defined(ARDUINO_ARCH_RP2040)

View File

@@ -4,7 +4,19 @@
#include "StringFormatter.h"
#define VERSION "4.2.45"
#define VERSION "4.2.54"
// 4.2.54 - EX8874 shield in config.example.h
// - Fix: Better warnings for pin number errors
// - Fix: Default roster list possible in Withrottle and <jR>
// - Fix: Pin handling supports pins up to 254
// 4.2.53 - Fix: Fault pin handling made more straight forward
// 4.2.52 - Experimental support for sabertooth motor controller on ESP32
// 4.2.51 - Add DISABLE_PROG to disable programming to save RAM/Flash
// 4.2.50 - Fixes: estop all, turnout eeprom, cab ID check
// 4.2.49 - Exrail SPEED take notice of external direction change
// 4.2.48 - BROADCAST/WITHROTTLE Exrail macros
// 4.2.47 - Correct response to <JA 0>
// 4.2.46 - Support boards with inverted fault pin
// 4.2.45 - Add ONCLOCKMINS to FastClock to allow hourly repeat events
// 4.2.44 - Add PowerShell installer EX-CommandStation-installer.exe
// 4.2.43 - Fix STM32 set right port mode bits for analog