From 74f7af16751095deabe2fbfa9ebf59707c4a2cea Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 3 Jan 2024 02:36:07 +0100 Subject: [PATCH 01/54] Display network IP fix --- GITHUB_SHA.h | 2 +- WifiESP32.cpp | 2 +- version.h | 3 ++- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 42646fe..4ece558 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202312251647Z" +#define GITHUB_SHA "devel-202401030135Z" diff --git a/WifiESP32.cpp b/WifiESP32.cpp index c990495..2aef5d1 100644 --- a/WifiESP32.cpp +++ b/WifiESP32.cpp @@ -179,7 +179,7 @@ bool WifiESP::setup(const char *SSid, if (WiFi.status() == WL_CONNECTED) { // DIAG(F("Wifi STA IP %s"),WiFi.localIP().toString().c_str()); DIAG(F("Wifi in STA mode")); - LCD(7, F("IP: %s"), WiFi.softAPIP().toString().c_str()); + LCD(7, F("IP: %s"), WiFi.localIP().toString().c_str()); wifiUp = true; } else { DIAG(F("Could not connect to Wifi SSID %s"),SSid); diff --git a/version.h b/version.h index bc79b3e..4ac82a5 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.17" +#define VERSION "5.2.18" +// 5.2.18 - Display network IP fix // 5.2.17 - ESP32 simplify network logic // 5.2.16 - Bugfix to allow for devices using the EX-IOExpander protocol to have no analogue or no digital pins // 5.2.15 - move call to CommandDistributor::broadcastPower() into the TrackManager::setTrackPower(*) functions From 4a3d3228a93622d8a7ab48cf1b0000079a51b208 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 7 Jan 2024 22:22:38 +0100 Subject: [PATCH 02/54] ESP32: Use SOC_RMT_MEM_WORDS_PER_CHANNEL to determine if the RMT hardware can handle DCC --- DCCRMT.cpp | 50 +++++++++++++++++++++++++++++++++++--------------- DCCWaveform.h | 8 ++++---- 2 files changed, 39 insertions(+), 19 deletions(-) diff --git a/DCCRMT.cpp b/DCCRMT.cpp index cbd9af6..afada7b 100644 --- a/DCCRMT.cpp +++ b/DCCRMT.cpp @@ -1,5 +1,5 @@ /* - * © 2021-2022, Harald Barth. + * © 2021-2024, Harald Barth. * * This file is part of DCC-EX * @@ -25,6 +25,18 @@ #include "DCCWaveform.h" // for MAX_PACKET_SIZE #include "soc/gpio_sig_map.h" +// check for right type of ESP32 +#include "soc/soc_caps.h" +#ifndef SOC_RMT_MEM_WORDS_PER_CHANNEL +#error This symobol should be defined +#endif +#if SOC_RMT_MEM_WORDS_PER_CHANNEL < 64 +#warning This is not an ESP32-WROOM but some other unsupported variant +#warning You are outside of the DCC-EX supported hardware +#endif + +static const byte RMT_CHAN_PER_DCC_CHAN = 2; + // Number of bits resulting out of X bytes of DCC payload data // Each byte has one bit extra and at the end we have one EOF marker #define DATA_LEN(X) ((X)*9+1) @@ -75,12 +87,30 @@ void IRAM_ATTR interrupt(rmt_channel_t channel, void *t) { RMTChannel::RMTChannel(pinpair pins, bool isMain) { byte ch; byte plen; + + // Below we check if the DCC packet actually fits into the RMT hardware + // Currently MAX_PACKET_SIZE = 5 so with checksum there are + // MAX_PACKET_SIZE+1 data packets. Each need DATA_LEN (9) bits. + // To that we add the preamble length, the fencepost DCC end bit + // and the RMT EOF marker. + // SOC_RMT_MEM_WORDS_PER_CHANNEL is either 64 (original WROOM) or + // 48 (all other ESP32 like the -C3 or -S2 + // The formula to get the possible MAX_PACKET_SIZE is + // + // ALLOCATED = RMT_CHAN_PER_DCC_CHAN * SOC_RMT_MEM_WORDS_PER_CHANNEL + // MAX_PACKET_SIZE = floor((ALLOCATED - PREAMBLE_LEN - 2)/9 - 1) + // + if (isMain) { ch = 0; plen = PREAMBLE_BITS_MAIN; + static_assert (DATA_LEN(MAX_PACKET_SIZE+1) + PREAMBLE_BITS_MAIN + 2 <= RMT_CHAN_PER_DCC_CHAN * SOC_RMT_MEM_WORDS_PER_CHANNEL, + "Number of DCC packet bits greater than ESP32 RMT memory available"); } else { - ch = 2; + ch = RMT_CHAN_PER_DCC_CHAN; // number == offset plen = PREAMBLE_BITS_PROG; + static_assert (DATA_LEN(MAX_PACKET_SIZE+1) + PREAMBLE_BITS_PROG + 2 <= RMT_CHAN_PER_DCC_CHAN * SOC_RMT_MEM_WORDS_PER_CHANNEL, + "Number of DCC packet bits greater than ESP32 RMT memory available"); } // preamble @@ -115,7 +145,7 @@ RMTChannel::RMTChannel(pinpair pins, bool isMain) { // data: max packet size today is 5 + checksum maxDataLen = DATA_LEN(MAX_PACKET_SIZE+1); // plus checksum data = (rmt_item32_t*)malloc(maxDataLen*sizeof(rmt_item32_t)); - + rmt_config_t config; // Configure the RMT channel for TX bzero(&config, sizeof(rmt_config_t)); @@ -123,20 +153,10 @@ RMTChannel::RMTChannel(pinpair pins, bool isMain) { config.channel = channel = (rmt_channel_t)ch; config.clk_div = RMT_CLOCK_DIVIDER; config.gpio_num = (gpio_num_t)pins.pin; - config.mem_block_num = 2; // With longest DCC packet 11 inc checksum (future expansion) - // number of bits needed is 22preamble + start + - // 11*9 + extrazero + EOT = 124 - // 2 mem block of 64 RMT items should be enough - + config.mem_block_num = RMT_CHAN_PER_DCC_CHAN; + // use config ESP_ERROR_CHECK(rmt_config(&config)); addPin(pins.invpin, true); - /* - // test: config another gpio pin - gpio_num_t gpioNum = (gpio_num_t)(pin-1); - PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[gpioNum], PIN_FUNC_GPIO); - gpio_set_direction(gpioNum, GPIO_MODE_OUTPUT); - gpio_matrix_out(gpioNum, RMT_SIG_OUT0_IDX, 0, 0); - */ // NOTE: ESP_INTR_FLAG_IRAM is *NOT* included in this bitmask ESP_ERROR_CHECK(rmt_driver_install(config.channel, 0, ESP_INTR_FLAG_LOWMED|ESP_INTR_FLAG_SHARED)); diff --git a/DCCWaveform.h b/DCCWaveform.h index 2202b53..1392288 100644 --- a/DCCWaveform.h +++ b/DCCWaveform.h @@ -2,7 +2,7 @@ * © 2021 M Steve Todd * © 2021 Mike S * © 2021 Fred Decker - * © 2020-2021 Harald Barth + * © 2020-2024 Harald Barth * © 2020-2021 Chris Harlow * All rights reserved. * @@ -33,9 +33,9 @@ // Number of preamble bits. -const int PREAMBLE_BITS_MAIN = 16; -const int PREAMBLE_BITS_PROG = 22; -const byte MAX_PACKET_SIZE = 5; // NMRA standard extended packets, payload size WITHOUT checksum. +const byte PREAMBLE_BITS_MAIN = 16; +const byte PREAMBLE_BITS_PROG = 22; +const byte MAX_PACKET_SIZE = 5; // NMRA standard extended packets, payload size WITHOUT checksum. // The WAVE_STATE enum is deliberately numbered because a change of order would be catastrophic From 39d0cbb791020e69be0a1da37a4ba7dcdc3a33e5 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 7 Jan 2024 22:24:15 +0100 Subject: [PATCH 03/54] version 5.2.19 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 4ece558..79fd3fe 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401030135Z" +#define GITHUB_SHA "devel-202401072123Z" diff --git a/version.h b/version.h index 4ac82a5..ee6bd24 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.18" +#define VERSION "5.2.19" +// 5.2.19 - ESP32: Determine if the RMT hardware can handle DCC // 5.2.18 - Display network IP fix // 5.2.17 - ESP32 simplify network logic // 5.2.16 - Bugfix to allow for devices using the EX-IOExpander protocol to have no analogue or no digital pins From 70a1b9538c303613328cadc554af13d5bb23c9bf Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 8 Jan 2024 13:19:22 +0100 Subject: [PATCH 04/54] Check return of Ethernet.begin() in all code variants --- EthernetInterface.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/EthernetInterface.cpp b/EthernetInterface.cpp index 5cf531c..7d8d7b0 100644 --- a/EthernetInterface.cpp +++ b/EthernetInterface.cpp @@ -59,15 +59,15 @@ EthernetInterface::EthernetInterface() DCCTimer::getSimulatedMacAddress(mac); connected=false; - #ifdef IP_ADDRESS - Ethernet.begin(mac, IP_ADDRESS); - #else +#ifdef IP_ADDRESS + if (Ethernet.begin(mac, IP_ADDRESS) == 0) +#else if (Ethernet.begin(mac) == 0) +#endif { DIAG(F("Ethernet.begin FAILED")); return; } - #endif if (Ethernet.hardwareStatus() == EthernetNoHardware) { DIAG(F("Ethernet shield not found or W5100")); } From 718e78fca686c4dee836e0e84ab3c9a1556ab054 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 8 Jan 2024 13:20:29 +0100 Subject: [PATCH 05/54] version 5.2.20 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 79fd3fe..1cc285a 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401072123Z" +#define GITHUB_SHA "devel-202401081219Z" diff --git a/version.h b/version.h index ee6bd24..75c2899 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.19" +#define VERSION "5.2.20" +// 5.2.20 - Check return of Ethernet.begin() // 5.2.19 - ESP32: Determine if the RMT hardware can handle DCC // 5.2.18 - Display network IP fix // 5.2.17 - ESP32 simplify network logic From b51a8fe126d75bddc96ab5e6f1742a0c6be2da61 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Tue, 9 Jan 2024 10:41:29 +1000 Subject: [PATCH 06/54] Add STARTUP_DELAY --- CommandStation-EX.ino | 5 +++++ config.example.h | 8 ++++++++ version.h | 3 ++- 3 files changed, 15 insertions(+), 1 deletion(-) diff --git a/CommandStation-EX.ino b/CommandStation-EX.ino index 205babf..9c94606 100644 --- a/CommandStation-EX.ino +++ b/CommandStation-EX.ino @@ -76,6 +76,11 @@ void setup() DIAG(F("License GPLv3 fsf.org (c) dcc-ex.com")); +// If user has defined a startup delay, delay here before starting IO +#if defined(STARTUP_DELAY) + delay(STARTUP_DELAY) +#endif + // Initialise HAL layer before reading EEprom or setting up MotorDrivers IODevice::begin(); diff --git a/config.example.h b/config.example.h index 89d6c1f..a2e08b2 100644 --- a/config.example.h +++ b/config.example.h @@ -222,6 +222,14 @@ The configuration file for DCC-EX Command Station // We do not support to use the same address, for example 100(long) and 100(short) // at the same time, there must be a border. +///////////////////////////////////////////////////////////////////////////////////// +// Some newer 32bit microcontrollers boot very quickly, so powering on I2C and other +// peripheral devices at the same time may result in the CommandStation booting too +// quickly to detect them. +// To work around this, uncomment the STARTUP_DELAY line below and set a value in +// milliseconds that works for your environment, default is 3000 (3 seconds). +// #define STARTUP_DELAY 3000 + ///////////////////////////////////////////////////////////////////////////////////// // // DEFINE TURNOUTS/ACCESSORIES FOLLOW NORM RCN-213 diff --git a/version.h b/version.h index 75c2899..9f19afe 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.20" +#define VERSION "5.2.21" +// 5.2.21 - Add STARTUP_DELAY config option to delay CS bootup // 5.2.20 - Check return of Ethernet.begin() // 5.2.19 - ESP32: Determine if the RMT hardware can handle DCC // 5.2.18 - Display network IP fix From 5ac26ce505b28c7f0a0a76b2d4e39b6b51b6cc5c Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Tue, 9 Jan 2024 10:49:22 +1000 Subject: [PATCH 07/54] Add missing ; and DIAG message --- CommandStation-EX.ino | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/CommandStation-EX.ino b/CommandStation-EX.ino index 9c94606..2cd9d33 100644 --- a/CommandStation-EX.ino +++ b/CommandStation-EX.ino @@ -78,7 +78,8 @@ void setup() // If user has defined a startup delay, delay here before starting IO #if defined(STARTUP_DELAY) - delay(STARTUP_DELAY) + DIAG(F("Delaying startup for %dms"), STARTUP_DELAY); + delay(STARTUP_DELAY); #endif // Initialise HAL layer before reading EEprom or setting up MotorDrivers From ca380d11dcaf01459614d2527577a08eb00cb43b Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 10 Jan 2024 08:15:30 +0100 Subject: [PATCH 08/54] Do not crash on turnouts or turntables without description --- EXRAIL2.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index cc3269b..8a2eadf 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -333,13 +333,15 @@ if (compileFeatures & FEATURE_SIGNAL) { } void RMFT2::setTurnoutHiddenState(Turnout * t) { - // turnout descriptions are in low flash F strings - t->setHidden(GETFLASH(getTurnoutDescription(t->getId()))==0x01); + // turnout descriptions are in low flash F strings + const FSH *desc = getTurnoutDescription(t->getId()); + if (desc) t->setHidden(GETFLASH(desc)==0x01); } #ifndef IO_NO_HAL void RMFT2::setTurntableHiddenState(Turntable * tto) { - tto->setHidden(GETFLASH(getTurntableDescription(tto->getId()))==0x01); + const FSH *desc = getTurntableDescription(tto->getId()); + if (desc) tto->setHidden(GETFLASH(desc)==0x01); } #endif From 27bd4448845e82b8d5d614dcc2d412bbde975c1c Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 10 Jan 2024 08:18:14 +0100 Subject: [PATCH 09/54] Numbers for automations/routes can be negative --- EXRAIL2Parser.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/EXRAIL2Parser.cpp b/EXRAIL2Parser.cpp index b049699..d231342 100644 --- a/EXRAIL2Parser.cpp +++ b/EXRAIL2Parser.cpp @@ -134,7 +134,7 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 return; } if (paramCount==2) { // - uint16_t id=p[1]; + int16_t id=p[1]; StringFormatter::send(stream,F("\n"), id, getRouteType(id), getRouteDescription(id)); From 796d5c47748a4c189f2b04c1e3215f6f54a2c9b2 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 10 Jan 2024 08:20:14 +0100 Subject: [PATCH 10/54] version 5.2.22 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 1cc285a..a53b57a 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401081219Z" +#define GITHUB_SHA "devel-202401100719Z" diff --git a/version.h b/version.h index 9f19afe..3c33933 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.21" +#define VERSION "5.2.22" +// 5.2.22 - Bugfixes: Empty turnout descriptions ok; negative route numbers valid. // 5.2.21 - Add STARTUP_DELAY config option to delay CS bootup // 5.2.20 - Check return of Ethernet.begin() // 5.2.19 - ESP32: Determine if the RMT hardware can handle DCC From 2e4995cab364893b37796cffd79ce992c1b1e47f Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 10 Jan 2024 11:58:30 +0000 Subject: [PATCH 11/54] Keyword Hasher _hk --- DCCEXParser.cpp | 154 ++++++++++++++++------------------------------ EXRAIL2Parser.cpp | 52 +++++----------- KeywordHasher.h | 57 +++++++++++++++++ TrackManager.cpp | 36 ++++------- 4 files changed, 137 insertions(+), 162 deletions(-) create mode 100644 KeywordHasher.h diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index aefed4c..47665c5 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -116,6 +116,7 @@ Once a new OPCODE is decided upon, update this list. #include "EXRAIL2.h" #include "Turntables.h" #include "version.h" +#include "KeywordHasher.h" // This macro can't be created easily as a portable function because the // flashlist requires a far pointer for high flash access. @@ -126,57 +127,6 @@ Once a new OPCODE is decided upon, update this list. 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_MAIN = 11339; -const int16_t HASH_KEYWORD_CABS = -11981; -const int16_t HASH_KEYWORD_RAM = 25982; -const int16_t HASH_KEYWORD_CMD = 9962; -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 -const int16_t HASH_KEYWORD_LIMIT = 27413; -const int16_t HASH_KEYWORD_MAX = 16244; -const int16_t HASH_KEYWORD_MIN = 15978; -const int16_t HASH_KEYWORD_RESET = 26133; -const int16_t HASH_KEYWORD_RETRY = 25704; -const int16_t HASH_KEYWORD_SPEED28 = -17064; -const int16_t HASH_KEYWORD_SPEED128 = 25816; -const int16_t HASH_KEYWORD_SERVO=27709; -const int16_t HASH_KEYWORD_TT=2688; -const int16_t HASH_KEYWORD_VPIN=-415; -const int16_t HASH_KEYWORD_A='A'; -const int16_t HASH_KEYWORD_C='C'; -const int16_t HASH_KEYWORD_G='G'; -const int16_t HASH_KEYWORD_H='H'; -const int16_t HASH_KEYWORD_I='I'; -const int16_t HASH_KEYWORD_M='M'; -const int16_t HASH_KEYWORD_O='O'; -const int16_t HASH_KEYWORD_P='P'; -const int16_t HASH_KEYWORD_R='R'; -const int16_t HASH_KEYWORD_T='T'; -const int16_t HASH_KEYWORD_X='X'; -const int16_t HASH_KEYWORD_LCN = 15137; -const int16_t HASH_KEYWORD_HAL = 10853; -const int16_t HASH_KEYWORD_SHOW = -21309; -const int16_t HASH_KEYWORD_ANIN = -10424; -const int16_t HASH_KEYWORD_ANOUT = -26399; -const int16_t HASH_KEYWORD_WIFI = -5583; -const int16_t HASH_KEYWORD_ETHERNET = -30767; -const int16_t HASH_KEYWORD_WIT = 31594; -const int16_t HASH_KEYWORD_EXTT = 8573; -const int16_t HASH_KEYWORD_ADD = 3201; - int16_t DCCEXParser::stashP[MAX_COMMAND_PARAMS]; bool DCCEXParser::stashBusy; Print *DCCEXParser::stashStream = NULL; @@ -567,20 +517,20 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) TrackManager::setTrackPower(TRACK_MODE_ALL, POWERMODE::ON); } if (params==1) { - if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN> + if (p[0]=="MAIN"_hk) { // <1 MAIN> TrackManager::setTrackPower(TRACK_MODE_MAIN, POWERMODE::ON); } #ifndef DISABLE_PROG - else if (p[0] == HASH_KEYWORD_JOIN) { // <1 JOIN> + else if (p[0] == "JOIN"_hk) { // <1 JOIN> TrackManager::setJoin(true); TrackManager::setTrackPower(TRACK_MODE_MAIN|TRACK_MODE_PROG, POWERMODE::ON); } - else if (p[0]==HASH_KEYWORD_PROG) { // <1 PROG> + else if (p[0]=="PROG"_hk) { // <1 PROG> TrackManager::setJoin(false); TrackManager::setTrackPower(TRACK_MODE_PROG, POWERMODE::ON); } #endif - else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H> + else if (p[0] >= "A"_hk && p[0] <= "H"_hk) { // <1 A-H> byte t = (p[0] - 'A'); TrackManager::setTrackPower(POWERMODE::ON, t); //StringFormatter::send(stream, F("\n"), t+'A'); @@ -600,17 +550,17 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) TrackManager::setTrackPower(TRACK_MODE_ALL, POWERMODE::OFF); } if (params==1) { - if (p[0]==HASH_KEYWORD_MAIN) { // <0 MAIN> + if (p[0]=="MAIN"_hk) { // <0 MAIN> TrackManager::setJoin(false); TrackManager::setTrackPower(TRACK_MODE_MAIN, POWERMODE::OFF); } #ifndef DISABLE_PROG - else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG> + else if (p[0]=="PROG"_hk) { // <0 PROG> TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off TrackManager::setTrackPower(TRACK_MODE_PROG, POWERMODE::OFF); } #endif - else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H> + else if (p[0] >= "A"_hk && p[0] <= "H"_hk) { // <1 A-H> byte t = (p[0] - 'A'); TrackManager::setJoin(false); TrackManager::setTrackPower(POWERMODE::OFF, t); @@ -704,7 +654,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) //if ((params<1) | (params>2)) break; // int16_t id=(params==2)?p[1]:0; switch(p[0]) { - case HASH_KEYWORD_C: // sets time and speed + case "C"_hk: // sets time and speed if (params==1) { // returns latest time int16_t x = CommandDistributor::retClockTime(); StringFormatter::send(stream, F("\n"), x); @@ -713,28 +663,28 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) CommandDistributor::setClockTime(p[1], p[2], 1); return; - case HASH_KEYWORD_G: // current gauge limits + case "G"_hk: // current gauge limits if (params>1) break; TrackManager::reportGauges(stream); // return; - case HASH_KEYWORD_I: // current values + case "I"_hk: // current values if (params>1) break; TrackManager::reportCurrent(stream); // return; - case HASH_KEYWORD_A: // intercepted by EXRAIL// returns automations/routes + case "A"_hk: // intercepted by EXRAIL// returns automations/routes if (params!=1) break; // StringFormatter::send(stream, F("\n")); return; - case HASH_KEYWORD_M: // intercepted by EXRAIL + case "M"_hk: // intercepted by EXRAIL if (params>1) break; // invalid cant do // requests stash size so say none. StringFormatter::send(stream,F("\n")); return; - case HASH_KEYWORD_R: // returns rosters + case "R"_hk: // returns rosters StringFormatter::send(stream, F("\n")); return; - case HASH_KEYWORD_T: // returns turnout list + case "T"_hk: // returns turnout list StringFormatter::send(stream, F(" for ( Turnout * t=Turnout::first(); t; t=t->next()) { @@ -780,7 +730,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) return; // No turntables without HAL support #ifndef IO_NO_HAL - case HASH_KEYWORD_O: // for (Turntable * tto=Turntable::first(); tto; tto=tto->next()) { @@ -805,7 +755,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } } return; - case HASH_KEYWORD_P: // returns turntable position list for the turntable id + case "P"_hk: // returns turntable position list for the turntable id if (params==2) { // Turntable *tto=Turntable::get(id); if (!tto || tto->isHidden()) { @@ -972,14 +922,14 @@ bool DCCEXParser::parseT(Print *stream, int16_t params, int16_t p[]) switch (p[1]) { // Turnout messages use 1=throw, 0=close. case 0: - case HASH_KEYWORD_C: + case "C"_hk: state = true; break; case 1: - case HASH_KEYWORD_T: + case "T"_hk: state= false; break; - case HASH_KEYWORD_X: + case "X"_hk: { Turnout *tt = Turnout::get(p[0]); if (tt) { @@ -996,14 +946,14 @@ bool DCCEXParser::parseT(Print *stream, int16_t params, int16_t p[]) } default: // Anything else is some kind of turnout create function. - if (params == 6 && p[1] == HASH_KEYWORD_SERVO) { // + if (params == 6 && p[1] == "SERVO"_hk) { // if (!ServoTurnout::create(p[0], (VPIN)p[2], (uint16_t)p[3], (uint16_t)p[4], (uint8_t)p[5])) return false; } else - if (params == 3 && p[1] == HASH_KEYWORD_VPIN) { // + if (params == 3 && p[1] == "VPIN"_hk) { // if (!VpinTurnout::create(p[0], p[2])) return false; } else - if (params >= 3 && p[1] == HASH_KEYWORD_DCC) { + if (params >= 3 && p[1] == "DCC"_hk) { // 0<=addr<=511, 0<=subadd<=3 (like command). if (params==4 && p[2]>=0 && p[2]<512 && p[3]>=0 && p[3]<4) { // if (!DCCTurnout::create(p[0], p[2], p[3])) return false; @@ -1069,41 +1019,41 @@ bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) { switch (p[0]) { #ifndef DISABLE_PROG - case HASH_KEYWORD_PROGBOOST: + case "PROGBOOST"_hk: TrackManager::progTrackBoosted=true; return true; #endif - case HASH_KEYWORD_RESET: + case "RESET"_hk: DCCTimer::reset(); break; // and if we didnt restart - case HASH_KEYWORD_SPEED28: + case "SPEED28"_hk: DCC::setGlobalSpeedsteps(28); DIAG(F("28 Speedsteps")); return true; - case HASH_KEYWORD_SPEED128: + case "SPEED128"_hk: DCC::setGlobalSpeedsteps(128); DIAG(F("128 Speedsteps")); return true; #ifndef DISABLE_PROG - case HASH_KEYWORD_ACK: // + case "ACK"_hk: // if (params >= 3) { - if (p[1] == HASH_KEYWORD_LIMIT) { + if (p[1] == "LIMIT"_hk) { DCCACK::setAckLimit(p[2]); LCD(1, F("Ack Limit=%dmA"), p[2]); // - } else if (p[1] == HASH_KEYWORD_MIN) { + } else if (p[1] == "MIN"_hk) { DCCACK::setMinAckPulseDuration(p[2]); LCD(0, F("Ack Min=%uus"), p[2]); // - } else if (p[1] == HASH_KEYWORD_MAX) { + } else if (p[1] == "MAX"_hk) { DCCACK::setMaxAckPulseDuration(p[2]); LCD(0, F("Ack Max=%uus"), p[2]); // - } else if (p[1] == HASH_KEYWORD_RETRY) { + } else if (p[1] == "RETRY"_hk) { if (p[2] >255) p[2]=3; LCD(0, F("Ack Retry=%d Sum=%d"), p[2], DCCACK::setAckRetry(p[2])); // } } else { - bool onOff = (params > 0) && (p[1] == 1 || p[1] == HASH_KEYWORD_ON); // dont care if other stuff or missing... just means off + bool onOff = (params > 0) && (p[1] == 1 || p[1] == "ON"_hk); // dont care if other stuff or missing... just means off DIAG(F("Ack diag %S"), onOff ? F("on") : F("off")); Diag::ACK = onOff; @@ -1121,64 +1071,64 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) { if (params == 0) return false; - bool onOff = (params > 0) && (p[1] == 1 || p[1] == HASH_KEYWORD_ON); // dont care if other stuff or missing... just means off + bool onOff = (params > 0) && (p[1] == 1 || p[1] == "ON"_hk); // dont care if other stuff or missing... just means off switch (p[0]) { - case HASH_KEYWORD_CABS: // + case "CABS"_hk: // DCC::displayCabList(stream); return true; - case HASH_KEYWORD_RAM: // + case "RAM"_hk: // DIAG(F("Free memory=%d"), DCCTimer::getMinimumFreeMemory()); return true; - case HASH_KEYWORD_CMD: // + case "CMD"_hk: // Diag::CMD = onOff; return true; #ifdef HAS_ENOUGH_MEMORY - case HASH_KEYWORD_WIFI: // + case "WIFI"_hk: // Diag::WIFI = onOff; return true; - case HASH_KEYWORD_ETHERNET: // + case "ETHERNET"_hk: // Diag::ETHERNET = onOff; return true; - case HASH_KEYWORD_WIT: // + case "WIT"_hk: // Diag::WITHROTTLE = onOff; return true; - case HASH_KEYWORD_LCN: // + case "LCN"_hk: // Diag::LCN = onOff; return true; #endif #ifndef DISABLE_EEPROM - case HASH_KEYWORD_EEPROM: // + case "EEPROM"_hk: // if (params >= 2) EEStore::dump(p[1]); return true; #endif - case HASH_KEYWORD_SERVO: // + case "SERVO"_hk: // - case HASH_KEYWORD_ANOUT: // + case "ANOUT"_hk: // IODevice::writeAnalogue(p[1], p[2], params>3 ? p[3] : 0); break; - case HASH_KEYWORD_ANIN: // Display analogue input value + case "ANIN"_hk: // Display analogue input value DIAG(F("VPIN=%u value=%d"), p[1], IODevice::readAnalogue(p[1])); break; #if !defined(IO_NO_HAL) - case HASH_KEYWORD_HAL: - if (p[1] == HASH_KEYWORD_SHOW) + case "HAL"_hk: + if (p[1] == "SHOW"_hk) IODevice::DumpAll(); - else if (p[1] == HASH_KEYWORD_RESET) + else if (p[1] == "RESET"_hk) IODevice::reset(); break; #endif - case HASH_KEYWORD_TT: // + case "TT"_hk: // IODevice::writeAnalogue(p[1], p[2], params>3 ? p[3] : 0); break; @@ -1232,7 +1182,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) case 3: // | - rotate to position for EX-Turntable or create DCC turntable { Turntable *tto = Turntable::get(p[0]); - if (p[1] == HASH_KEYWORD_DCC) { + if (p[1] == "DCC"_hk) { if (tto || p[2] < 0 || p[2] > 3600) return false; if (!DCCTurntable::create(p[0])) return false; Turntable *tto = Turntable::get(p[0]); @@ -1249,7 +1199,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) case 4: // create an EXTT turntable { Turntable *tto = Turntable::get(p[0]); - if (p[1] == HASH_KEYWORD_EXTT) { + if (p[1] == "EXTT"_hk) { if (tto || p[3] < 0 || p[3] > 3600) return false; if (!EXTTTurntable::create(p[0], (VPIN)p[2])) return false; Turntable *tto = Turntable::get(p[0]); @@ -1264,7 +1214,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) case 5: // add a position { Turntable *tto = Turntable::get(p[0]); - if (p[1] == HASH_KEYWORD_ADD) { + if (p[1] == "ADD"_hk) { // tto must exist, no more than 48 positions, angle 0 - 3600 if (!tto || p[2] > 48 || p[4] < 0 || p[4] > 3600) return false; tto->addPosition(p[2], p[3], p[4]); diff --git a/EXRAIL2Parser.cpp b/EXRAIL2Parser.cpp index b049699..872d27a 100644 --- a/EXRAIL2Parser.cpp +++ b/EXRAIL2Parser.cpp @@ -28,25 +28,7 @@ #include "defines.h" #include "EXRAIL2.h" #include "DCC.h" -// Command parsing keywords -const int16_t HASH_KEYWORD_EXRAIL=15435; -const int16_t HASH_KEYWORD_ON = 2657; -const int16_t HASH_KEYWORD_START=23232; -const int16_t HASH_KEYWORD_RESERVE=11392; -const int16_t HASH_KEYWORD_FREE=-23052; -const int16_t HASH_KEYWORD_LATCH=1618; -const int16_t HASH_KEYWORD_UNLATCH=1353; -const int16_t HASH_KEYWORD_PAUSE=-4142; -const int16_t HASH_KEYWORD_RESUME=27609; -const int16_t HASH_KEYWORD_KILL=5218; -const int16_t HASH_KEYWORD_ALL=3457; -const int16_t HASH_KEYWORD_ROUTES=-3702; -const int16_t HASH_KEYWORD_RED=26099; -const int16_t HASH_KEYWORD_AMBER=18713; -const int16_t HASH_KEYWORD_GREEN=-31493; -const int16_t HASH_KEYWORD_A='A'; -const int16_t HASH_KEYWORD_M='M'; - +#include "KeywordHasher.h" // This filter intercepts <> commands to do the following: // - Implement RMFT specific commands/diagnostics @@ -58,8 +40,8 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 switch(opcode) { case 'D': - if (p[0]==HASH_KEYWORD_EXRAIL) { // - diag = paramCount==2 && (p[1]==HASH_KEYWORD_ON || p[1]==1); + if (p[0]=="EXRAIL"_hk) { // + diag = paramCount==2 && (p[1]=="ON"_hk || p[1]==1); opcode=0; } break; @@ -125,7 +107,7 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 case 'J': // throttle info commands if (paramCount<1) return; switch(p[0]) { - case HASH_KEYWORD_A: // returns automations/routes + case "A"_hk: // returns automations/routes if (paramCount==1) {// StringFormatter::send(stream, F("stream(stream); @@ -152,7 +134,7 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 return; } break; - case HASH_KEYWORD_M: + case "M"_hk: // NOTE: we only need to handle valid calls here because // DCCEXParser has to have code to handle the cases where // exrail isnt involved anyway. @@ -236,13 +218,13 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { return true; } switch (p[0]) { - case HASH_KEYWORD_PAUSE: // + case "PAUSE"_hk: // if (paramCount!=1) return false; DCC::setThrottle(0,1,true); // pause all locos on the track pausingTask=(RMFT2 *)1; // Impossible task address return true; - case HASH_KEYWORD_RESUME: // + case "RESUME"_hk: // if (paramCount!=1) return false; pausingTask=NULL; { @@ -256,7 +238,7 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { return true; - case HASH_KEYWORD_START: // + case "START"_hk: // if (paramCount<2 || paramCount>3) return false; { int route=(paramCount==2) ? p[1] : p[2]; @@ -273,7 +255,7 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { } // check KILL ALL here, otherwise the next validation confuses ALL with a flag - if (p[0]==HASH_KEYWORD_KILL && p[1]==HASH_KEYWORD_ALL) { + if (p[0]=="KILL"_hk && p[1]=="ALL"_hk) { while (loopTask) loopTask->kill(F("KILL ALL")); // destructor changes loopTask return true; } @@ -282,7 +264,7 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { if (paramCount!=2 ) return false; switch (p[0]) { - case HASH_KEYWORD_KILL: // Kill taskid|ALL + case "KILL"_hk: // Kill taskid|ALL { if ( p[1]<0 || p[1]>=MAX_FLAGS) return false; RMFT2 * task=loopTask; @@ -297,27 +279,27 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { } return false; - case HASH_KEYWORD_RESERVE: // force reserve a section + case "RESERVE"_hk: // force reserve a section return setFlag(p[1],SECTION_FLAG); - case HASH_KEYWORD_FREE: // force free a section + case "FREE"_hk: // force free a section return setFlag(p[1],0,SECTION_FLAG); - case HASH_KEYWORD_LATCH: + case "LATCH"_hk: return setFlag(p[1], LATCH_FLAG); - case HASH_KEYWORD_UNLATCH: + case "UNLATCH"_hk: return setFlag(p[1], 0, LATCH_FLAG); - case HASH_KEYWORD_RED: + case "RED"_hk: doSignal(p[1],SIGNAL_RED); return true; - case HASH_KEYWORD_AMBER: + case "AMBER"_hk: doSignal(p[1],SIGNAL_AMBER); return true; - case HASH_KEYWORD_GREEN: + case "GREEN"_hk: doSignal(p[1],SIGNAL_GREEN); return true; diff --git a/KeywordHasher.h b/KeywordHasher.h new file mode 100644 index 0000000..d30f566 --- /dev/null +++ b/KeywordHasher.h @@ -0,0 +1,57 @@ +/* + * © 2024 Vincent Hamp and Chris Harlow + * All rights reserved. + * + * This file is part of CommandStation-EX + * + * This is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * It is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with CommandStation. If not, see . + */ + + +/* Reader be aware: + This function implements the _hk data type so that a string keyword + is hashed to the same value as the DCCEXParser uses to hash incoming + keywords. + Thus "MAIN"_hk generates exactly the same run time vakue + as const int16_t HASH_KEYWORD_MAIN=11339 +*/ +#ifndef KeywordHAsher_h +#define KeywordHasher_h + +#include +constexpr uint16_t CompiletimeKeywordHasher(const char * sv, uint16_t running=0) { + return (*sv==0) ? running : CompiletimeKeywordHasher(sv+1, + (*sv >= '0' && *sv <= '9') + ? (10*running+*sv-'0') // Numeric hash + : ((running << 5) + running) ^ *sv + ); // +} + +constexpr int16_t operator""_hk(const char * keyword, size_t len) +{ + return (int16_t) CompiletimeKeywordHasher(keyword,len*0); +} + +/* Some historical values for testing: +const int16_t HASH_KEYWORD_MAIN = 11339; +const int16_t HASH_KEYWORD_SLOW = -17209; +const int16_t HASH_KEYWORD_SPEED28 = -17064; +const int16_t HASH_KEYWORD_SPEED128 = 25816; +*/ + +static_assert("MAIN"_hk == 11339); +static_assert("SLOW"_hk == -17209); +static_assert("SPEED28"_hk == -17064); +static_assert("SPEED128"_hk == 25816); +#endif \ No newline at end of file diff --git a/TrackManager.cpp b/TrackManager.cpp index 4a501a1..da96832 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -28,6 +28,7 @@ #include "DIAG.h" #include "CommandDistributor.h" #include "DCCEXParser.h" +#include "KeywordHasher.h" // Virtualised Motor shield multi-track hardware Interface #define FOR_EACH_TRACK(t) for (byte t=0;t<=lastTrack;t++) @@ -35,21 +36,6 @@ FOR_EACH_TRACK(t) \ if (track[t]->getMode()==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_NONE = -26550; -const int16_t HASH_KEYWORD_DC = 2183; -const int16_t HASH_KEYWORD_DCX = 6463; // DC reversed polarity -const int16_t HASH_KEYWORD_EXT = 8201; // External DCC signal -const int16_t HASH_KEYWORD_A = 65; // parser makes single chars the ascii. -const int16_t HASH_KEYWORD_AUTO = -5457; -#ifdef BOOSTER_INPUT -const int16_t HASH_KEYWORD_BOOST = 11269; -#endif -const int16_t HASH_KEYWORD_INV = 11857; MotorDriver * TrackManager::track[MAX_TRACKS]; int16_t TrackManager::trackDCAddr[MAX_TRACKS]; @@ -362,38 +348,38 @@ bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[]) } - p[0]-=HASH_KEYWORD_A; // convert A... to 0.... + p[0]-="A"_hk; // convert A... to 0.... if (params>1 && (p[0]<0 || p[0]>=MAX_TRACKS)) return false; - if (params==2 && p[1]==HASH_KEYWORD_MAIN) // <= id MAIN> + if (params==2 && p[1]=="MAIN"_hk) // <= id MAIN> return setTrackMode(p[0],TRACK_MODE_MAIN); #ifndef DISABLE_PROG - if (params==2 && p[1]==HASH_KEYWORD_PROG) // <= id PROG> + if (params==2 && p[1]=="PROG"_hk) // <= id PROG> return setTrackMode(p[0],TRACK_MODE_PROG); #endif - if (params==2 && (p[1]==HASH_KEYWORD_OFF || p[1]==HASH_KEYWORD_NONE)) // <= id OFF> <= id NONE> + if (params==2 && (p[1]=="OFF"_hk || p[1]=="NONE"_hk)) // <= id OFF> <= id NONE> return setTrackMode(p[0],TRACK_MODE_NONE); - if (params==2 && p[1]==HASH_KEYWORD_EXT) // <= id EXT> + if (params==2 && p[1]=="EXT"_hk) // <= id EXT> return setTrackMode(p[0],TRACK_MODE_EXT); #ifdef BOOSTER_INPUT - if (params==2 && p[1]==HASH_KEYWORD_BOOST) // <= id BOOST> + if (params==2 && p[1]=="BOOST"_hk) // <= id BOOST> return setTrackMode(p[0],TRACK_MODE_BOOST); #endif - if (params==2 && p[1]==HASH_KEYWORD_AUTO) // <= id AUTO> + if (params==2 && p[1]=="AUTO"_hk) // <= id AUTO> return setTrackMode(p[0], track[p[0]]->getMode() | TRACK_MODE_AUTOINV); - if (params==2 && p[1]==HASH_KEYWORD_INV) // <= id AUTO> + if (params==2 && p[1]=="INV"_hk) // <= id AUTO> return setTrackMode(p[0], track[p[0]]->getMode() | TRACK_MODE_INV); - if (params==3 && p[1]==HASH_KEYWORD_DC && p[2]>0) // <= id DC cab> + if (params==3 && p[1]=="DC"_hk && p[2]>0) // <= id DC cab> return setTrackMode(p[0],TRACK_MODE_DC,p[2]); - if (params==3 && p[1]==HASH_KEYWORD_DCX && p[2]>0) // <= id DCX cab> + if (params==3 && p[1]=="DCX"_hk && p[2]>0) // <= id DCX cab> return setTrackMode(p[0],TRACK_MODE_DC|TRACK_MODE_INV,p[2]); return false; From 43648fd9f4df5a1fdbc9053a95de1b803866792f Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 10 Jan 2024 12:01:40 +0000 Subject: [PATCH 12/54] 5.2.23 --- version.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index 3c33933..d849eae 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.22" +#define VERSION "5.2.23" +// 5.2.23 - KeywordHasher _hk (no functional change) // 5.2.22 - Bugfixes: Empty turnout descriptions ok; negative route numbers valid. // 5.2.21 - Add STARTUP_DELAY config option to delay CS bootup // 5.2.20 - Check return of Ethernet.begin() From d8c282434cea0f939b8768066948b7e55f570952 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 10 Jan 2024 12:11:14 +0000 Subject: [PATCH 13/54] _hk in myAutomation --- DCCEX.h | 1 + 1 file changed, 1 insertion(+) diff --git a/DCCEX.h b/DCCEX.h index 2dc8eb7..3aa7b7a 100644 --- a/DCCEX.h +++ b/DCCEX.h @@ -49,6 +49,7 @@ #include "CommandDistributor.h" #include "TrackManager.h" #include "DCCTimer.h" +#include "KeywordHasher.h" #include "EXRAIL.h" #endif From 9ab6b3d4eae983f07ed4192c511960581fd03a84 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 10 Jan 2024 15:09:22 +0100 Subject: [PATCH 14/54] Bugfix: Ethernet fixed IP start --- EthernetInterface.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/EthernetInterface.cpp b/EthernetInterface.cpp index 7d8d7b0..34e209a 100644 --- a/EthernetInterface.cpp +++ b/EthernetInterface.cpp @@ -47,6 +47,10 @@ void EthernetInterface::setup() }; +#ifdef IP_ADDRESS +static IPAddress myIP(IP_ADDRESS); +#endif + /** * @brief Aquire IP Address from DHCP and start server * @@ -60,14 +64,14 @@ EthernetInterface::EthernetInterface() connected=false; #ifdef IP_ADDRESS - if (Ethernet.begin(mac, IP_ADDRESS) == 0) + Ethernet.begin(mac, myIP); #else if (Ethernet.begin(mac) == 0) -#endif { DIAG(F("Ethernet.begin FAILED")); return; } +#endif if (Ethernet.hardwareStatus() == EthernetNoHardware) { DIAG(F("Ethernet shield not found or W5100")); } @@ -136,7 +140,7 @@ bool EthernetInterface::checkLink() { DIAG(F("Ethernet cable connected")); connected=true; #ifdef IP_ADDRESS - Ethernet.setLocalIP(IP_ADDRESS); // for static IP, set it again + Ethernet.setLocalIP(myIP); // for static IP, set it again #endif IPAddress ip = Ethernet.localIP(); // look what IP was obtained (dynamic or static) server = new EthernetServer(IP_PORT); // Ethernet Server listening on default port IP_PORT From d24d09c37a3e2a457bd3f630f64d28827b8221ec Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 10 Jan 2024 15:10:25 +0100 Subject: [PATCH 15/54] subversion --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index a53b57a..759a0cc 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401100719Z" +#define GITHUB_SHA "devel-202401101409Z" From 20ae915eaf82c85626bf52134c10310d7c3ecef7 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 10 Jan 2024 15:23:52 +0100 Subject: [PATCH 16/54] remove unused ccr_reg variable --- I2CManager_STM32.h | 1 - 1 file changed, 1 deletion(-) diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index 7e0f547..7e9e63e 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -110,7 +110,6 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { // Calculate a rise time appropriate to the requested bus speed // Use 10x the rise time spec to enable integer divide of 50ns clock period uint16_t t_rise; - uint32_t ccr_freq; while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further // writes to CR1 while STOP is being executed! From a508ee7055edfbc72de4aa5559f31869f213006d Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 10 Jan 2024 16:08:11 +0000 Subject: [PATCH 17/54] Fix asserts for Teensy --- KeywordHasher.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/KeywordHasher.h b/KeywordHasher.h index d30f566..d232bd2 100644 --- a/KeywordHasher.h +++ b/KeywordHasher.h @@ -50,8 +50,8 @@ const int16_t HASH_KEYWORD_SPEED28 = -17064; const int16_t HASH_KEYWORD_SPEED128 = 25816; */ -static_assert("MAIN"_hk == 11339); -static_assert("SLOW"_hk == -17209); -static_assert("SPEED28"_hk == -17064); -static_assert("SPEED128"_hk == 25816); +static_assert("MAIN"_hk == 11339,"Keyword hasher error"); +static_assert("SLOW"_hk == -17209,"Keyword hasher error"); +static_assert("SPEED28"_hk == -17064,"Keyword hasher error"); +static_assert("SPEED128"_hk == 25816,"Keyword hasher error"); #endif \ No newline at end of file From a54a262f6841c7a1b150b171e1a69bebbf3ead96 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Sun, 14 Jan 2024 02:03:42 +0000 Subject: [PATCH 18/54] 5.2.24 EXRAIL asserts --- EXRAILMacros.h | 64 ++++++++++++++++++++++++++++++++++++++++++++++++++ version.h | 6 ++++- 2 files changed, 69 insertions(+), 1 deletion(-) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index f79693d..2c18ae0 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -74,6 +74,70 @@ #define ALIAS(name,value...) const int name= 1##value##0 ==10 ? -__COUNTER__ : value##0/10; #include "myAutomation.h" +// Pass 1d Detect sequence duplicates. +// This pass generates no runtime data or code +#include "EXRAIL2MacroReset.h" +#undef AUTOMATION +#define AUTOMATION(id, description) id, +#undef ROUTE +#define ROUTE(id, description) id, +#undef SEQUENCE +#define SEQUENCE(id) id, +constexpr int16_t compileTimeSequenceList[]={ + #include "myAutomation.h" + 0 + }; +constexpr int16_t stuffSize=sizeof(compileTimeSequenceList)/sizeof(int16_t) - 1; + + +// Compile time function to check for sequence nos. +constexpr bool hasseq(const int16_t value, const uint16_t pos=0 ) { + return pos>=stuffSize? false : + compileTimeSequenceList[pos]==value + || hasseq(value,pos+1); +} + +// Compile time function to check for duplicate sequence nos. +constexpr bool hasdup(const int16_t value, const uint16_t pos ) { + return pos>=stuffSize? false : + compileTimeSequenceList[pos]==value + || hasseq(value,pos+1) + || hasdup(compileTimeSequenceList[pos],pos+1); +} + + +static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AUTOMATION detected"); + +//pass 1s static asserts to +// - check call and follows etc for existing sequence numbers +// - check range on LATCH/UNLATCH +// This pass generates no runtime data or code +#include "EXRAIL2MacroReset.h" +#undef CALL +#define CALL(id) static_assert(hasseq(id),"Sequence not found"); +#undef FOLLOW +#define FOLLOW(id) static_assert(hasseq(id),"Sequence not found"); +#undef START +#define START(id) static_assert(hasseq(id),"Sequence not found"); +#undef SENDLOCO +#define SENDLOCO(cab,id) static_assert(hasseq(id),"Sequence not found"); +#undef LATCH +#define LATCH(id) static_assert(id>=0 && id=0 && id=0 && id=0 && id=0 && speed<128,"Speed out of valid range 0-127"); +#undef FWD +#define FWD(speed) static_assert(speed>=0 && speed<128,"Speed out of valid range 0-127"); +#undef REV +#define REV(speed) static_assert(speed>=0 && speed<128,"Speed out of valid range 0-127"); + +#include "myAutomation.h" + // Pass 1h Implements HAL macro by creating exrailHalSetup function // Also allows creating EXTurntable object #include "EXRAIL2MacroReset.h" diff --git a/version.h b/version.h index d849eae..15b7e5d 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,11 @@ #include "StringFormatter.h" -#define VERSION "5.2.23" +#define VERSION "5.2.24" +// 5.2.24 - Exrail macro asserts to catch +// : duplicate/missing automation/route/sequence/call ids +// : latches and reserves out of range +// : speeds out of range // 5.2.23 - KeywordHasher _hk (no functional change) // 5.2.22 - Bugfixes: Empty turnout descriptions ok; negative route numbers valid. // 5.2.21 - Add STARTUP_DELAY config option to delay CS bootup From 8216579f62e166bcaf474fa182162233d1cbbec2 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Sun, 14 Jan 2024 02:09:22 +0000 Subject: [PATCH 19/54] 5.2.25 returns bugs --- DCCEXParser.cpp | 8 ++++---- version.h | 3 ++- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 47665c5..16f4494 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1113,11 +1113,11 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) case "ANOUT"_hk: // IODevice::writeAnalogue(p[1], p[2], params>3 ? p[3] : 0); - break; + return true; case "ANIN"_hk: // Display analogue input value DIAG(F("VPIN=%u value=%d"), p[1], IODevice::readAnalogue(p[1])); - break; + return true; #if !defined(IO_NO_HAL) case "HAL"_hk: @@ -1125,12 +1125,12 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) IODevice::DumpAll(); else if (p[1] == "RESET"_hk) IODevice::reset(); - break; + return true; #endif case "TT"_hk: // IODevice::writeAnalogue(p[1], p[2], params>3 ? p[3] : 0); - break; + return true; default: // invalid/unknown return parseC(stream, params, p); diff --git a/version.h b/version.h index 15b7e5d..33c6164 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.24" +#define VERSION "5.2.25" +// 5.2.25 - Fix bug causing after working Date: Sun, 14 Jan 2024 20:20:22 +0000 Subject: [PATCH 20/54] HAL defaults control --- EXRAIL2MacroReset.h | 2 ++ EXRAILMacros.h | 7 ++++++- IODevice.cpp | 44 ++++++++++++++++++++++---------------------- IODevice.h | 3 ++- version.h | 4 +++- 5 files changed, 35 insertions(+), 25 deletions(-) diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 7811a0d..3554f6c 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -67,6 +67,7 @@ #undef FWD #undef GREEN #undef HAL +#undef HAL_IGNORE_DEFAULTS #undef IF #undef IFAMBER #undef IFCLOSED @@ -218,6 +219,7 @@ #define FWD(speed) #define GREEN(signal_id) #define HAL(haltype,params...) +#define HAL_IGNORE_DEFAULTS #define IF(sensor_id) #define IFAMBER(signal_id) #define IFCLOSED(turnout_id) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 2c18ae0..8ed2b82 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -143,8 +143,12 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU #include "EXRAIL2MacroReset.h" #undef HAL #define HAL(haltype,params...) haltype::create(params); -void exrailHalSetup() { +#undef HAL_IGNORE_DEFAULTS +#define HAL_IGNORE_DEFAULTS ignore_defaults=true; +bool exrailHalSetup() { + bool ignore_defaults=false; #include "myAutomation.h" + return ignore_defaults; } // Pass 1c detect compile time featurtes @@ -460,6 +464,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define FWD(speed) OPCODE_FWD,V(speed), #define GREEN(signal_id) OPCODE_GREEN,V(signal_id), #define HAL(haltype,params...) +#define HAL_IGNORE_DEFAULTS #define IF(sensor_id) OPCODE_IF,V(sensor_id), #define IFAMBER(signal_id) OPCODE_IFAMBER,V(signal_id), #define IFCLOSED(turnout_id) OPCODE_IFCLOSED,V(turnout_id), diff --git a/IODevice.cpp b/IODevice.cpp index e811fff..99199aa 100644 --- a/IODevice.cpp +++ b/IODevice.cpp @@ -33,7 +33,7 @@ // Link to halSetup function. If not defined, the function reference will be NULL. extern __attribute__((weak)) void halSetup(); -extern __attribute__((weak)) void exrailHalSetup(); +extern __attribute__((weak)) bool exrailHalSetup(); //================================================================================================================== // Static methods @@ -60,34 +60,31 @@ void IODevice::begin() { halSetup(); // include any HAL devices defined in exrail. + bool ignoreDefaults=false; if (exrailHalSetup) - exrailHalSetup(); - + ignoreDefaults=exrailHalSetup(); + if (ignoreDefaults) return; + // Predefine two PCA9685 modules 0x40-0x41 if no conflicts // Allocates 32 pins 100-131 - if (checkNoOverlap(100, 16, 0x40)) { + const bool silent=true; // no message if these conflict + if (checkNoOverlap(100, 16, 0x40, silent)) { PCA9685::create(100, 16, 0x40); - } else { - DIAG(F("Default PCA9685 at I2C 0x40 disabled due to configured user device")); - } - if (checkNoOverlap(116, 16, 0x41)) { + } + + if (checkNoOverlap(116, 16, 0x41, silent)) { PCA9685::create(116, 16, 0x41); - } else { - DIAG(F("Default PCA9685 at I2C 0x41 disabled due to configured user device")); - } + } // Predefine two MCP23017 module 0x20/0x21 if no conflicts // Allocates 32 pins 164-195 - if (checkNoOverlap(164, 16, 0x20)) { + if (checkNoOverlap(164, 16, 0x20, silent)) { MCP23017::create(164, 16, 0x20); - } else { - DIAG(F("Default MCP23017 at I2C 0x20 disabled due to configured user device")); - } - if (checkNoOverlap(180, 16, 0x21)) { + } + + if (checkNoOverlap(180, 16, 0x21, silent)) { MCP23017::create(180, 16, 0x21); - } else { - DIAG(F("Default MCP23017 at I2C 0x21 disabled due to configured user device")); - } + } } // reset() function to reinitialise all devices @@ -339,7 +336,10 @@ IODevice *IODevice::findDeviceFollowing(VPIN vpin) { // returns true if pins DONT overlap with existing device // TODO: Move the I2C address reservation and checks into the I2CManager code. // That will enable non-HAL devices to reserve I2C addresses too. -bool IODevice::checkNoOverlap(VPIN firstPin, uint8_t nPins, I2CAddress i2cAddress) { +// Silent is used by the default setup so that there is no message if the default +// device has already been handled by the user setup. +bool IODevice::checkNoOverlap(VPIN firstPin, uint8_t nPins, + I2CAddress i2cAddress, bool silent) { #ifdef DIAG_IO DIAG(F("Check no overlap %u %u %s"), firstPin,nPins,i2cAddress.toString()); #endif @@ -352,14 +352,14 @@ bool IODevice::checkNoOverlap(VPIN firstPin, uint8_t nPins, I2CAddress i2cAddres VPIN lastDevPin=firstDevPin+dev->_nPins-1; bool noOverlap= firstPin>lastDevPin || lastPin_I2CAddress==i2cAddress) { - DIAG(F("WARNING HAL Overlap. i2c Addr %s ignored."),i2cAddress.toString()); + if (!silent) DIAG(F("WARNING HAL Overlap. i2c Addr %s ignored."),i2cAddress.toString()); return false; } } diff --git a/IODevice.h b/IODevice.h index d12fafd..6c70f5f 100644 --- a/IODevice.h +++ b/IODevice.h @@ -166,7 +166,8 @@ public: void setGPIOInterruptPin(int16_t pinNumber); // Method to check if pins will overlap before creating new device. - static bool checkNoOverlap(VPIN firstPin, uint8_t nPins=1, I2CAddress i2cAddress=0); + static bool checkNoOverlap(VPIN firstPin, uint8_t nPins=1, + I2CAddress i2cAddress=0, bool silent=false); // Method used by IODevice filters to locate slave pins that may be overlayed by their own // pin range. diff --git a/version.h b/version.h index 33c6164..8c8ef68 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.25" +#define VERSION "5.2.26" +// 5.2.26 - Silently ignore overridden HAL defaults +// - include HAL_IGNORE_DEFAULTS macro in EXRAIL // 5.2.25 - Fix bug causing after working Date: Thu, 18 Jan 2024 08:20:33 +0100 Subject: [PATCH 21/54] Bugfix: allocate enough bytes for digital pins. Add more sanity checks when allocating memory --- IO_EXIOExpander.h | 33 ++++++++++++++++++++++++--------- 1 file changed, 24 insertions(+), 9 deletions(-) diff --git a/IO_EXIOExpander.h b/IO_EXIOExpander.h index c8bcba0..b5c40c9 100644 --- a/IO_EXIOExpander.h +++ b/IO_EXIOExpander.h @@ -100,8 +100,14 @@ private: if (_digitalPinBytes < digitalBytesNeeded) { // Not enough space, free any existing buffer and allocate a new one if (_digitalPinBytes > 0) free(_digitalInputStates); - _digitalInputStates = (byte*) calloc(_digitalPinBytes, 1); - _digitalPinBytes = digitalBytesNeeded; + if ((_digitalInputStates = (byte*) calloc(digitalBytesNeeded, 1)) != NULL) { + _digitalPinBytes = digitalBytesNeeded; + } else { + DIAG(F("EX-IOExpander I2C:%s ERROR alloc %d bytes"), _I2CAddress.toString(), digitalBytesNeeded); + _deviceState = DEVSTATE_FAILED; + _digitalPinBytes = 0; + return; + } } } @@ -117,7 +123,16 @@ private: _analogueInputStates = (uint8_t*) calloc(analogueBytesNeeded, 1); _analogueInputBuffer = (uint8_t*) calloc(analogueBytesNeeded, 1); _analoguePinMap = (uint8_t*) calloc(_numAnaloguePins, 1); - _analoguePinBytes = analogueBytesNeeded; + if (_analogueInputStates != NULL && + _analogueInputBuffer != NULL && + _analoguePinMap != NULL) { + _analoguePinBytes = analogueBytesNeeded; + } else { + DIAG(F("EX-IOExpander I2C:%s ERROR alloc analog pin bytes"), _I2CAddress.toString()); + _deviceState = DEVSTATE_FAILED; + _analoguePinBytes = 0; + return; + } } } } else { @@ -364,14 +379,14 @@ private: uint8_t _minorVer = 0; uint8_t _patchVer = 0; - uint8_t* _digitalInputStates; - uint8_t* _analogueInputStates; - uint8_t* _analogueInputBuffer; // buffer for I2C input transfers + uint8_t* _digitalInputStates = NULL; + uint8_t* _analogueInputStates = NULL; + uint8_t* _analogueInputBuffer = NULL; // buffer for I2C input transfers uint8_t _readCommandBuffer[1]; - uint8_t _digitalPinBytes = 0; // Size of allocated memory buffer (may be longer than needed) - uint8_t _analoguePinBytes = 0; // Size of allocated memory buffers (may be longer than needed) - uint8_t* _analoguePinMap; + uint8_t _digitalPinBytes = 0; // Size of allocated memory buffer (may be longer than needed) + uint8_t _analoguePinBytes = 0; // Size of allocated memory buffer (may be longer than needed) + uint8_t* _analoguePinMap = NULL; I2CRB _i2crb; enum {RDS_IDLE, RDS_DIGITAL, RDS_ANALOGUE}; // Read operation states From bc37a2d2cf8d6eea6dd28fc97de7286a444604ce Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 18 Jan 2024 08:22:28 +0100 Subject: [PATCH 22/54] version 5.2.27 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 759a0cc..24f96c3 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401101409Z" +#define GITHUB_SHA "devel-202401180721Z" diff --git a/version.h b/version.h index 8c8ef68..3512451 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.26" +#define VERSION "5.2.27" +// 5.2.27 - Bugfix: IOExpander memory allocation // 5.2.26 - Silently ignore overridden HAL defaults // - include HAL_IGNORE_DEFAULTS macro in EXRAIL // 5.2.25 - Fix bug causing after working Date: Thu, 18 Jan 2024 18:56:15 +1000 Subject: [PATCH 23/54] Update EX-IOExpander copyright --- IO_EXIOExpander.h | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/IO_EXIOExpander.h b/IO_EXIOExpander.h index b5c40c9..191bf3c 100644 --- a/IO_EXIOExpander.h +++ b/IO_EXIOExpander.h @@ -1,5 +1,6 @@ /* * © 2022, Peter Cole. All rights reserved. + * © 2022, Harald Barth. All rights reserved. * * This file is part of EX-CommandStation * @@ -101,13 +102,13 @@ private: // Not enough space, free any existing buffer and allocate a new one if (_digitalPinBytes > 0) free(_digitalInputStates); if ((_digitalInputStates = (byte*) calloc(digitalBytesNeeded, 1)) != NULL) { - _digitalPinBytes = digitalBytesNeeded; - } else { - DIAG(F("EX-IOExpander I2C:%s ERROR alloc %d bytes"), _I2CAddress.toString(), digitalBytesNeeded); - _deviceState = DEVSTATE_FAILED; - _digitalPinBytes = 0; - return; - } + _digitalPinBytes = digitalBytesNeeded; + } else { + DIAG(F("EX-IOExpander I2C:%s ERROR alloc %d bytes"), _I2CAddress.toString(), digitalBytesNeeded); + _deviceState = DEVSTATE_FAILED; + _digitalPinBytes = 0; + return; + } } } From cf1e1c92b3b0f8d084def7f26f7aff5a3dcde3cd Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 20 Jan 2024 22:15:47 +0100 Subject: [PATCH 24/54] Check "easy" check first --- IO_EXIOExpander.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/IO_EXIOExpander.h b/IO_EXIOExpander.h index 191bf3c..2e83eb7 100644 --- a/IO_EXIOExpander.h +++ b/IO_EXIOExpander.h @@ -1,6 +1,6 @@ /* * © 2022, Peter Cole. All rights reserved. - * © 2022, Harald Barth. All rights reserved. + * © 2024, Harald Barth. All rights reserved. * * This file is part of EX-CommandStation * @@ -257,7 +257,7 @@ private: // If we're not doing anything now, check to see if a new input transfer is due. if (_readState == RDS_IDLE) { - if (currentMicros - _lastDigitalRead > _digitalRefresh && _numDigitalPins>0) { // Delay for digital read refresh + if (_numDigitalPins>0 && currentMicros - _lastDigitalRead > _digitalRefresh) { // Delay for digital read refresh // Issue new read request for digital states. As the request is non-blocking, the buffer has to // be allocated from heap (object state). _readCommandBuffer[0] = EXIORDD; @@ -265,7 +265,7 @@ private: // non-blocking read _lastDigitalRead = currentMicros; _readState = RDS_DIGITAL; - } else if (currentMicros - _lastAnalogueRead > _analogueRefresh && _numAnaloguePins>0) { // Delay for analogue read refresh + } else if (_numAnaloguePins>0 && currentMicros - _lastAnalogueRead > _analogueRefresh) { // Delay for analogue read refresh // Issue new read for analogue input states _readCommandBuffer[0] = EXIORDAN; I2CManager.read(_I2CAddress, _analogueInputBuffer, From 811bce4b2a8fdd26315fc843183a5ad801981c6e Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 20 Jan 2024 22:16:26 +0100 Subject: [PATCH 25/54] tag --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 24f96c3..d15db46 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401180721Z" +#define GITHUB_SHA "devel-202401202116Z" From 0a52a26d50d26d2d87109a229ec32c659c8e48d6 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 21 Jan 2024 21:09:55 +0100 Subject: [PATCH 26/54] ESP32: Can all Wifi channels. Only write Wifi password to display if it is a well known one --- WifiESP32.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/WifiESP32.cpp b/WifiESP32.cpp index 2aef5d1..e45d0e8 100644 --- a/WifiESP32.cpp +++ b/WifiESP32.cpp @@ -164,6 +164,8 @@ bool WifiESP::setup(const char *SSid, if (haveSSID && havePassword && !forceAP) { WiFi.setHostname(hostname); // Strangely does not work unless we do it HERE! WiFi.mode(WIFI_STA); + WiFi.setScanMethod(WIFI_ALL_CHANNEL_SCAN); // Scan all channels so we find strongest + // (default in Wifi library is first match) #ifdef SERIAL_BT_COMMANDS WiFi.setSleep(true); #else @@ -204,7 +206,7 @@ bool WifiESP::setup(const char *SSid, if (!haveSSID || forceAP) { // prepare all strings String strSSID(forceAP ? SSid : "DCCEX_"); - String strPass(forceAP ? password : "PASS_"); + String strPass( (forceAP && havePassword) ? password : "PASS_"); if (!forceAP) { String strMac = WiFi.macAddress(); strMac.remove(0,9); @@ -228,7 +230,8 @@ bool WifiESP::setup(const char *SSid, // DIAG(F("Wifi AP SSID %s PASS %s"),strSSID.c_str(),havePassword ? password : strPass.c_str()); DIAG(F("Wifi in AP mode")); LCD(5, F("Wifi: %s"), strSSID.c_str()); - LCD(6, F("PASS: %s"),havePassword ? password : strPass.c_str()); + if (!havePassword) + LCD(6, F("PASS: %s"),strPass.c_str()); // DIAG(F("Wifi AP IP %s"),WiFi.softAPIP().toString().c_str()); LCD(7, F("IP: %s"),WiFi.softAPIP().toString().c_str()); wifiUp = true; From 6d0740eab4512a3b54acec0c6e34860f2e028f8a Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 21 Jan 2024 21:11:57 +0100 Subject: [PATCH 27/54] version 5.2.28 --- GITHUB_SHA.h | 2 +- version.h | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index d15db46..8aa2bd8 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401202116Z" +#define GITHUB_SHA "devel-202401212011Z" diff --git a/version.h b/version.h index 3512451..e94303f 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.27" +#define VERSION "5.2.28" +// 5.2.28 - ESP32: Can all Wifi channels. +// - ESP32: Only write Wifi password to display if it is a well known one // 5.2.27 - Bugfix: IOExpander memory allocation // 5.2.26 - Silently ignore overridden HAL defaults // - include HAL_IGNORE_DEFAULTS macro in EXRAIL From 3c4e4bb14de63e85eac23b6e7d0d9843874979d7 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 3 Feb 2024 19:05:56 +0000 Subject: [PATCH 28/54] Added support for DFPLayer over I2c - IO_I2CDFPlayerh Added IO_I2CDFPlayer.h to support DFPLayer over I2C connected to NXP SC16IS750/SC16IS752 (currently only single UART for SC16IS752) Added enhanced IO_I2CDFPLayer enum commands to EXRAIL2.h Added PLAYSOUND alias of ANOUT to EXRAILMacros.h EXRail additions as per advice from Chris --- EXRAIL2.h | 19 ++ EXRAILMacros.h | 4 + I2CManager.cpp | 4 +- IO_I2CDFPlayer.h | 803 +++++++++++++++++++++++++++++++++++++++++++++++ version.h | 6 +- 5 files changed, 834 insertions(+), 2 deletions(-) create mode 100644 IO_I2CDFPlayer.h diff --git a/EXRAIL2.h b/EXRAIL2.h index 30a2f45..6652526 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -258,4 +258,23 @@ private: #define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter) #define SKIPOP progCounter+=3 +// IO_I2CDFPlayer commands and values +enum : uint8_t{ + PLAY = 0x0F, + VOL = 0x06, + FOLDER = 0x2B, // Not a DFPlayer command, used to set folder nr where audio file is + REPEATPLAY = 0x08, + STOPPLAY = 0x16, + EQ = 0x07, // Set equaliser, require parameter NORMAL, POP, ROCK, JAZZ, CLASSIC or BASS + RESET = 0x0C, + DACON = 0x1A, + SETAM = 0x2A, // Set audio mixer 1 or 2 for this DFPLayer (future use) + NORMAL = 0x00, // Equalizer parameters + POP = 0x01, + ROCK = 0x02, + JAZZ = 0x03, + CLASSIC = 0x04, + BASS = 0x05, + }; + #endif diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 8ed2b82..98af846 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -59,6 +59,10 @@ // helper macro for turnout description as HIDDEN #define HIDDEN "\x01" +// PLAYSOUND is alias of ANOUT to make the user experience of a Conductor beter for +// playing sounds with IO_I2CDFPlayer +#define PLAYSOUND ANOUT + // helper macro to strip leading zeros off time inputs // (10#mins)%100) #define STRIP_ZERO(value) 10##value%100 diff --git a/I2CManager.cpp b/I2CManager.cpp index 1d1387e..2c115fa 100644 --- a/I2CManager.cpp +++ b/I2CManager.cpp @@ -54,6 +54,8 @@ static const FSH * guessI2CDeviceType(uint8_t address) { return F("Time-of-flight sensor"); else if (address >= 0x3c && address <= 0x3d) return F("OLED Display"); + else if (address >= 0x48 && address <= 0x57) // SC16IS752x UART detection + return F("SC16IS75x UART"); else if (address >= 0x48 && address <= 0x4f) return F("Analogue Inputs or PWM"); else if (address >= 0x40 && address <= 0x4f) @@ -363,4 +365,4 @@ void I2CAddress::toHex(const uint8_t value, char *buffer) { /* static */ bool I2CAddress::_addressWarningDone = false; -#endif \ No newline at end of file +#endif diff --git a/IO_I2CDFPlayer.h b/IO_I2CDFPlayer.h new file mode 100644 index 0000000..79fa16b --- /dev/null +++ b/IO_I2CDFPlayer.h @@ -0,0 +1,803 @@ + /* + * © 2023, Neil McKechnie. All rights reserved. + * + * This file is part of DCC++EX API + * + * This is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * It is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with CommandStation. If not, see . + */ + +/* + * DFPlayer is an MP3 player module with an SD card holder. It also has an integrated + * amplifier, so it only needs a power supply and a speaker. + * This driver is a modified version of the IO_DFPlayer.h file + * ********************************************************************************************* + * + * Dec 2023, Added NXP SC16IS752 I2C Dual UART to enable the DFPlayer connection over the I2C bus + * The SC16IS752 has 64 bytes TX & RX FIFO buffer + * First version without interrupts from I2C UART and only RX/TX are used, interrupts may not be + * needed as the RX Fifo holds the reply + * + * Jan 2024, Issue with using both UARTs simultaniously, the secod uart seems to work but the first transmit + * corrupt data. This need more analysis and experimenatation. + * Will push this driver to the dev branch with the uart fixed to 0 + * Both SC16IS750 (single uart) and SC16IS752 (dual uart, but only uart 0 is enable) + * + * myHall.cpp configuration syntax: + * + * I2CDFPlayer::create(1st vPin, vPins, I2C address, xtal); + * + * Parameters: + * 1st vPin : First virtual pin that EX-Rail can control to play a sound, use PLAYSOUND command (alias of ANOUT) + * vPins : Total number of virtual pins allocated (2 vPins are supported, one for each UART) + * 1st vPin for UART 0, 2nd for UART 1 + * I2C Address : I2C address of the serial controller, in 0x format + * xtal : 0 for 1,8432Mhz, 1 for 14,7456Mhz + * + * The vPin is also a pin that can be read, it indicate if the DFPlayer has finished playing a track + * + */ + +#ifndef IO_I2CDFPlayer_h +#define IO_I2CDFPlayer_h + +#include "IODevice.h" +#include "I2CManager.h" +#include "DIAG.h" + +// Debug and diagnostic defines, enable too many will result in slowing the driver +//#define DIAG_I2CDFplayer +//#define DIAG_I2CDFplayer_data +//#define DIAG_I2CDFplayer_reg +//#define DIAG_I2CDFplayer_playing + +class I2CDFPlayer : public IODevice { +private: + const uint8_t MAXVOLUME=30; + uint8_t RETRYCOUNT = 0x03; + bool _playing = false; + uint8_t _inputIndex = 0; + unsigned long _commandSendTime; // Time (us) that last transmit took place. + unsigned long _timeoutTime; + uint8_t _recvCMD; // Last received command code byte + bool _awaitingResponse = false; + uint8_t _retryCounter = RETRYCOUNT; // Max retries before timing out + uint8_t _requestedVolumeLevel = MAXVOLUME; + uint8_t _currentVolume = MAXVOLUME; + int _requestedSong = -1; // -1=none, 0=stop, >0=file number + bool _repeat = false; // audio file is repeat playing + uint8_t _previousCmd = true; + // SC16IS752 defines + I2CAddress _I2CAddress; + I2CRB _rb; + uint8_t _UART_CH=0x00; // Fix uart ch to 0 for now + // Communication parameters for the DFPlayer are fixed at 8 bit, No parity, 1 stopbit + uint8_t WORD_LEN = 0x03; // Value LCR bit 0,1 + uint8_t STOP_BIT = 0x00; // Value LCR bit 2 + uint8_t PARITY_ENA = 0x00; // Value LCR bit 3 + uint8_t PARITY_TYPE = 0x00; // Value LCR bit 4 + uint32_t BAUD_RATE = 9600; + uint8_t PRESCALER = 0x01; // Value MCR bit 7 + uint8_t TEMP_REG_VAL = 0x00; + uint8_t FIFO_RX_LEVEL = 0x00; + uint8_t RX_BUFFER = 0x00; // nr of bytes copied into _inbuffer + uint8_t FIFO_TX_LEVEL = 0x00; + bool _playCmd = false; + bool _volCmd = false; + bool _folderCmd = false; + uint8_t _requestedFolder = 0x01; // default to folder 01 + uint8_t _currentFolder = 0x01; // default to folder 01 + bool _repeatCmd = false; + bool _stopplayCmd = false; + bool _resetCmd = false; + bool _eqCmd = false; + uint8_t _requestedEQValue = NORMAL; + uint8_t _currentEQvalue = NORMAL; // start equalizer value + bool _daconCmd = false; + uint8_t _audioMixer = 0x01; // Default to output amplifier 1 + bool _setamCmd = false; // Set the Audio mixer channel + uint8_t _outbuffer [11]; // DFPlayer command is 10 bytes + 1 byte register address & UART channel + uint8_t _inbuffer[10]; // expected DFPlayer return 10 bytes + + unsigned long _sc16is752_xtal_freq; + unsigned long SC16IS752_XTAL_FREQ_LOW = 1843200; // To support cheap eBay/AliExpress SC16IS752 boards + unsigned long SC16IS752_XTAL_FREQ_HIGH = 14745600; // Support for higher baud rates, standard for modular EX-IO system + +public: + // Constructor + I2CDFPlayer(VPIN firstVpin, int nPins, I2CAddress i2cAddress, uint8_t xtal){ + _firstVpin = firstVpin; + _nPins = nPins; + _I2CAddress = i2cAddress; + if (xtal == 0){ + _sc16is752_xtal_freq = SC16IS752_XTAL_FREQ_LOW; + } else { // should be 1 + _sc16is752_xtal_freq = SC16IS752_XTAL_FREQ_HIGH; + } + addDevice(this); + } + +public: + static void create(VPIN firstVpin, int nPins, I2CAddress i2cAddress, uint8_t xtal) { + if (checkNoOverlap(firstVpin, nPins, i2cAddress)) new I2CDFPlayer(firstVpin, nPins, i2cAddress, xtal); + } + + void _begin() override { + // check if SC16IS752 exist first, initialize and then resume DFPlayer init via SC16IS752 + I2CManager.begin(); + I2CManager.setClock(1000000); + if (I2CManager.exists(_I2CAddress)){ + DIAG(F("SC16IS752 I2C:%s UART detected"), _I2CAddress.toString()); + Init_SC16IS752(); // Initialize UART + if (_deviceState == DEVSTATE_FAILED){ + DIAG(F("SC16IS752 I2C:%s UART initialization failed"), _I2CAddress.toString()); + } + } else { + DIAG(F("SC16IS752 I2C:%s UART not detected"), _I2CAddress.toString()); + } + #if defined(DIAG_IO) + _display(); + #endif + // Now init DFPlayer + // Send a query to the device to see if it responds + _deviceState = DEVSTATE_INITIALISING; + sendPacket(0x42,0,0); + _timeoutTime = micros() + 5000000UL; // 5 second timeout + _awaitingResponse = true; + } + + + void _loop(unsigned long currentMicros) override { + // Read responses from device + uint8_t status = _rb.status; + if (status == I2C_STATUS_PENDING) return; // Busy, so don't do anything + if (status == I2C_STATUS_OK) { + processIncoming(currentMicros); + // Check if a command sent to device has timed out. Allow 0.5 second for response + // added retry counter, sometimes we do not sent keep alive due to other commands sent to DFPlayer + if (_awaitingResponse && (int32_t)(currentMicros - _timeoutTime) > 0) { // timeout triggered + if(_retryCounter == 0){ // retry counter out of luck, must take the device to failed state + DIAG(F("I2CDFPlayer:%s, DFPlayer not responding on UART channel: 0x%x"), _I2CAddress.toString(), _UART_CH); + _deviceState = DEVSTATE_FAILED; + _awaitingResponse = false; + _playing = false; + _retryCounter = RETRYCOUNT; + } else { // timeout and retry protection and recovery of corrupt data frames from DFPlayer + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: %s, DFPlayer timout, retry counter: %d on UART channel: 0x%x"), _I2CAddress.toString(), _retryCounter, _UART_CH); + #endif + _timeoutTime = currentMicros + 5000000UL; // Timeout if no response within 5 seconds// reset timeout + _awaitingResponse = false; // trigger sending a keep alive 0x42 in processOutgoing() + _retryCounter --; // decrement retry counter + resetRX_fifo(); // reset the RX fifo as it has corrupt data + } + } + } + + status = _rb.status; + if (status == I2C_STATUS_PENDING) return; // Busy, try next time + if (status == I2C_STATUS_OK) { + // Send any commands that need to go. + processOutgoing(currentMicros); + } + delayUntil(currentMicros + 10000); // Only enter every 10ms + } + + + // Check for incoming data, and update busy flag and other state accordingly + + void processIncoming(unsigned long currentMicros) { + // Expected message is in the form "7E FF 06 3D xx xx xx xx xx EF" + RX_fifo_lvl(); + if (FIFO_RX_LEVEL >= 10) { + #ifdef DIAG_I2CDFplayer + DIAG(F("I2CDFPlayer: %s Retrieving data from RX Fifo on UART_CH: 0x%x FIFO_RX_LEVEL: %d"),_I2CAddress.toString(), _UART_CH, FIFO_RX_LEVEL); + #endif + _outbuffer[0] = REG_RHR << 3 | _UART_CH << 1; + // Only copy 10 bytes from RX FIFO, there maybe additional partial return data after a track is finished playing in the RX FIFO + I2CManager.read(_I2CAddress, _inbuffer, 10, _outbuffer, 1); // inbuffer[] has the data now + //delayUntil(currentMicros + 10000); // Allow time to get the data + RX_BUFFER = 10; // We have copied 10 bytes from RX FIFO to _inbuffer + #ifdef DIAG_I2CDFplayer_data + DIAG(F("SC16IS752: At I2C: %s, UART channel: 0x%x, RX FIFO Data"), _I2CAddress.toString(), _UART_CH); + for (int i = 0; i < sizeof _inbuffer; i++){ + DIAG(F("SC16IS752: Data _inbuffer[0x%x]: 0x%x"), i, _inbuffer[i]); + } + #endif + } else { + FIFO_RX_LEVEL = 0; //set to 0, we'll read a fresh FIFO_RX_LEVEL next time + return; // No data or not enough data in rx fifo, check again next time around + } + + + bool ok = false; + //DIAG(F("I2CDFPlayer: RX_BUFFER: %d"), RX_BUFFER); + while (RX_BUFFER != 0) { + int c = _inbuffer[_inputIndex]; // Start at 0, increment to FIFO_RX_LEVEL + switch (_inputIndex) { + case 0: + if (c == 0x7E) ok = true; + break; + case 1: + if (c == 0xFF) ok = true; + break; + case 2: + if (c== 0x06) ok = true; + break; + case 3: + _recvCMD = c; // CMD byte + ok = true; + break; + case 6: + switch (_recvCMD) { + //DIAG(F("I2CDFPlayer: %s, _recvCMD: 0x%x _awaitingResponse: 0x0%x"),_I2CAddress.toString(), _recvCMD, _awaitingResponse); + case 0x42: + // Response to status query + _playing = (c != 0); + // Mark the device online and cancel timeout + if (_deviceState==DEVSTATE_INITIALISING) { + _deviceState = DEVSTATE_NORMAL; + #ifdef DIAG_I2CDFplayer + DIAG(F("I2CDFPlayer: %s, UART_CH: 0x0%x, _deviceState: 0x0%x"),_I2CAddress.toString(), _UART_CH, _deviceState); + #endif + #ifdef DIAG_IO + _display(); + #endif + } + _awaitingResponse = false; + break; + case 0x3d: + // End of play + if (_playing) { + #ifdef DIAG_IO + DIAG(F("I2CDFPlayer: Finished")); + #endif + _playing = false; + } + break; + case 0x40: + // Error codes; 1: Module Busy + DIAG(F("I2CDFPlayer: Error %d returned from device"), c); + _playing = false; + break; + } + ok = true; + break; + case 4: case 5: case 7: case 8: + ok = true; // Skip over these bytes in message. + break; + case 9: + if (c==0xef) { + // Message finished + _retryCounter = RETRYCOUNT; // reset the retry counter as we have received a valid packet + } + break; + default: + break; + } + if (ok){ + _inputIndex++; // character as expected, so increment index + RX_BUFFER --; // Decrease FIFO_RX_LEVEL with each character read from _inbuffer[_inputIndex] + } else { + _inputIndex = 0; // otherwise reset. + RX_BUFFER = 0; + } + } + RX_BUFFER = 0; //Set to 0, we'll read a new RX FIFO level again + } + + + // Send any commands that need to be sent + void processOutgoing(unsigned long currentMicros) { + // When two commands are sent in quick succession, the device will often fail to + // execute one. Testing has indicated that a delay of 100ms or more is required + // between successive commands to get reliable operation. + // If 100ms has elapsed since the last thing sent, then check if there's some output to do. + if (((int32_t)currentMicros - _commandSendTime) > 100000) { + if ( _resetCmd == true){ + sendPacket(0x0C,0,0); + _resetCmd = false; + } else if(_volCmd == true) { // do the volme before palying a track + if(_requestedVolumeLevel >= 0 && _requestedVolumeLevel <= 30){ + _currentVolume = _requestedVolumeLevel; // If _requestedVolumeLevel is out of range, sent _currentV1olume + } + sendPacket(0x06, 0x00, _currentVolume); + _volCmd = false; + } else if (_playCmd == true) { + // Change song + if (_requestedSong != -1) { + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: _requestedVolumeLevel: %u, _requestedSong: %u, _currentFolder: %u _playCmd: 0x%x"), _requestedVolumeLevel, _requestedSong, _currentFolder, _playCmd); + #endif + sendPacket(0x0F, _currentFolder, _requestedSong); // audio file in folder + _requestedSong = -1; + _playCmd = false; + } + } //else if (_requestedSong == 0) { + else if (_stopplayCmd == true) { + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: Stop playing: _stopplayCmd: 0x%x"), _stopplayCmd); + #endif + sendPacket(0x16, 0x00, 0x00); // Stop playing + _requestedSong = -1; + _repeat = false; // reset repeat + _stopplayCmd = false; + } else if (_folderCmd == true) { + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: Folder: _folderCmd: 0x%x, _requestedFolder: %d"), _stopplayCmd, _requestedFolder); + #endif + if (_currentFolder != _requestedFolder){ + _currentFolder = _requestedFolder; + } + _folderCmd = false; + } else if (_repeatCmd == true) { + if(_repeat == false) { // No repeat play currently + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: Repeat: _repeatCmd: 0x%x, _requestedSong: %d, _repeat: 0x0%x"), _repeatCmd, _requestedSong, _repeat); + #endif + sendPacket(0x08, 0x00, _requestedSong); // repeat playing audio file in root folder + _requestedSong = -1; + _repeat = true; + } + _repeatCmd= false; + } else if (_daconCmd == true) { // Always turn DAC on + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: DACON: _daconCmd: 0x%x"), _daconCmd); + #endif + sendPacket(0x1A,0,0x00); + _daconCmd = false; + } else if (_eqCmd == true){ // Set Equalizer, values 0x00 - 0x05 + if (_currentEQvalue != _requestedEQValue){ + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: EQ: _eqCmd: 0x%x, _currentEQvalue: 0x0%x, _requestedEQValue: 0x0%x"), _eqCmd, _currentEQvalue, _requestedEQValue); + #endif + _currentEQvalue = _requestedEQValue; + sendPacket(0x07,0x00,_currentEQvalue); + } + _eqCmd = false; + } else if (_setamCmd == true){ // Set Audio mixer channel + setGPIO(); // Set the audio mixer channel + /* + if (_audioMixer == 1){ // set to audio mixer 1 + if (_UART_CH == 0){ + TEMP_REG_VAL |= (0x01 << _UART_CH); //Set GPIO pin 0 to high + } else { // must be UART 1 + TEMP_REG_VAL |= (0x01 << _UART_CH); //Set GPIO pin 1 to high + } + //_setamCmd = false; + //UART_WriteRegister(REG_IOSTATE, TEMP_REG_VAL); + } else { // set to audio mixer 2 + if (_UART_CH == 0){ + TEMP_REG_VAL &= (0x00 << _UART_CH); //Set GPIO pin 0 to Low + } else { // must be UART 1 + TEMP_REG_VAL &= (0x00 << _UART_CH); //Set GPIO pin 1 to Low + } + //_setamCmd = false; + //UART_WriteRegister(REG_IOSTATE, TEMP_REG_VAL); + }*/ + _setamCmd = false; + } else if ((int32_t)currentMicros - _commandSendTime > 1000000) { + // Poll device every second that other commands aren't being sent, + // to check if it's still connected and responding. + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: Send keepalive") ); + #endif + sendPacket(0x42,0,0); + if (!_awaitingResponse) { + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: Send keepalive, _awaitingResponse: 0x0%x"), _awaitingResponse ); + #endif + _timeoutTime = currentMicros + 5000000UL; // Timeout if no response within 5 seconds + _awaitingResponse = true; + } + } + } + } + + + // Write to a vPin will do nothing + void _write(VPIN vpin, int value) override { + if (_deviceState == DEVSTATE_FAILED) return; + #ifdef DIAG_IO + DIAG(F("I2CDFPlayer: Writing to any vPin not supported")); + #endif + } + + + // WriteAnalogue on first pin uses the nominated value as a file number to start playing, if file number > 0. + // Volume may be specified as second parameter to writeAnalogue. + // If value is zero, the player stops playing. + // WriteAnalogue on second pin sets the output volume. + // + // WriteAnalogue to be done on first vpin + // + //void _writeAnalogue(VPIN vpin, int value, uint8_t volume=0, uint16_t=0) override { + void _writeAnalogue(VPIN vpin, int value, uint8_t volume=0, uint16_t cmd=0) override { + if (_deviceState == DEVSTATE_FAILED) return; + #ifdef DIAG_IO + DIAG(F("I2CDFPlayer: VPIN:%u FileNo:%d Volume:%d Command:0x%x"), vpin, value, volume, cmd); + #endif + uint8_t pin = vpin - _firstVpin; + if (pin == 0) { // Enhanced DFPlayer commands, do nothing if not vPin 0 + // Read command and value + switch (cmd){ + //case NONE: + // DFPlayerCmd = cmd; + // break; + case PLAY: + _playCmd = true; + _volCmd = true; + _requestedSong = value; + _requestedVolumeLevel = volume; + _playing = true; + break; + case VOL: + _volCmd = true; + _requestedVolumeLevel = volume; + break; + case FOLDER: + _folderCmd = true; + if (volume <= 0 || volume > 99){ // Range checking, valid values 1-99, else default to 1 + _requestedFolder = 0x01; // if outside range, default to folder 01 + } else { + _requestedFolder = volume; + } + break; + case REPEATPLAY: // Need to check if _repeat == true, if so do nothing + if (_repeat == false) { + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: WriteAnalog Repeat: _repeat: 0x0%x, value: %d _repeatCmd: 0x%x"), _repeat, value, _repeatCmd); + #endif + _repeatCmd = true; + _requestedSong = value; + _requestedVolumeLevel = volume; + _playing = true; + } + break; + case STOPPLAY: + _stopplayCmd = true; + break; + case EQ: + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: WriteAnalog EQ: cmd: 0x%x, EQ value: 0x%x"), cmd, volume); + #endif + _eqCmd = true; + if (volume <= 0 || volume > 5) { // If out of range, default to NORMAL + _requestedEQValue = NORMAL; + } else { // Valid EQ parameter range + _requestedEQValue = volume; + } + break; + case RESET: + _resetCmd = true; + break; + case DACON: // Works, but without the DACOFF command limited value, except when not relying on DFPlayer default to turn the DAC on + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: WrtieAnalog DACON: cmd: 0x%x"), cmd); + #endif + _daconCmd = true; + break; + case SETAM: // Set the audio mixer channel to 1 or 2 + _setamCmd = true; + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: WrtieAnalog SETAM: cmd: 0x%x"), cmd); + #endif + if (volume <= 0 || volume > 2) { // If out of range, default to 1 + _audioMixer = 1; + } else { // Valid SETAM parameter in range + _audioMixer = volume; // _audioMixer valid values 1 or 2 + } + break; + default: + break; + } + } + } + + // A read on any pin indicates if the player is still playing. + int _read(VPIN vpin) override { + if (_deviceState == DEVSTATE_FAILED) return false; + uint8_t pin = vpin - _firstVpin; + if (pin == 0) { // Do nothing if not vPin 0 + return _playing; + } + } + + void _display() override { + DIAG(F("I2CDFPlayer Configured on Vpins:%u-%u %S"), _firstVpin, _firstVpin+_nPins-1, + (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F("")); + } + +private: + // DFPlayer command frame + // 7E FF 06 0F 00 01 01 xx xx EF + // 0 -> 7E is start code + // 1 -> FF is version + // 2 -> 06 is length + // 3 -> 0F is command + // 4 -> 00 is no receive + // 5~6 -> 01 01 is argument + // 7~8 -> checksum = 0 - ( FF+06+0F+00+01+01 ) + // 9 -> EF is end code + + void sendPacket(uint8_t command, uint8_t arg1 = 0, uint8_t arg2 = 0) { + FIFO_TX_LEVEL = 0; // Reset FIFO_TX_LEVEL + uint8_t out[] = { + 0x7E, + 0xFF, + 06, + command, + 00, + //static_cast(arg >> 8), + //static_cast(arg & 0x00ff), + arg1, + arg2, + 00, + 00, + 0xEF }; + + setChecksum(out); + + // Prepend the DFPlayer command with REG address and UART Channel in _outbuffer + _outbuffer[0] = REG_THR << 3 | _UART_CH << 1; //TX FIFO and UART Channel + for ( int i = 1; i < sizeof(out)+1 ; i++){ + _outbuffer[i] = out[i-1]; + } + + #ifdef DIAG_I2CDFplayer_data + DIAG(F("SC16IS752: I2C: %s Sent packet function"), _I2CAddress.toString()); + for (int i = 0; i < sizeof _outbuffer; i++){ + DIAG(F("SC16IS752: Data _outbuffer[0x%x]: 0x%x"), i, _outbuffer[i]); + } + #endif + + TX_fifo_lvl(); + if(FIFO_TX_LEVEL > 0){ //FIFO is empty + I2CManager.write(_I2CAddress, _outbuffer, sizeof(_outbuffer), &_rb); + //I2CManager.write(_I2CAddress, _outbuffer, sizeof(_outbuffer)); + #ifdef DIAG_I2CDFplayer + DIAG(F("SC16IS752: I2C: %s data transmit complete on UART: 0x%x"), _I2CAddress.toString(), _UART_CH); + #endif + } else { + DIAG(F("I2CDFPlayer at: %s, TX FIFO not empty on UART: 0x%x"), _I2CAddress.toString(), _UART_CH); + _deviceState = DEVSTATE_FAILED; // This should not happen + } + _commandSendTime = micros(); + } + + uint16_t calcChecksum(uint8_t* packet) + { + uint16_t sum = 0; + for (int i = 1; i < 7; i++) + { + sum += packet[i]; + } + return -sum; + } + + void setChecksum(uint8_t* out) + { + uint16_t sum = calcChecksum(out); + out[7] = (sum >> 8); + out[8] = (sum & 0xff); + } + + // SC16IS752 functions + // Initialise SC16IS752 only for this channel + // First a software reset + // Enable FIFO and clear TX & RX FIFO + // Need to set the following registers + // IOCONTROL set bit 1 and 2 to 0 indicating that they are GPIO + // IODIR set all bit to 1 indicating al are output + // IOSTATE set only bit 0 to 1 for UART 0, or only bit 1 for UART 1 // + // LCR bit 7=0 divisor latch (clock division registers DLH & DLL, they store 16 bit divisor), + // WORD_LEN, STOP_BIT, PARITY_ENA and PARITY_TYPE + // MCR bit 7=0 clock divisor devide-by-1 clock input + // DLH most significant part of divisor + // DLL least significant part of divisor + // + // BAUD_RATE, WORD_LEN, STOP_BIT, PARITY_ENA and PARITY_TYPE have been defined and initialized + // + void Init_SC16IS752(){ // Return value is in _deviceState + #ifdef DIAG_I2CDFplayer + DIAG(F("SC16IS752: Initialize I2C: %s , UART Ch: 0x%x"), _I2CAddress.toString(), _UART_CH); + #endif + //uint16_t _divisor = (SC16IS752_XTAL_FREQ / PRESCALER) / (BAUD_RATE * 16); + uint16_t _divisor = (_sc16is752_xtal_freq/PRESCALER)/(BAUD_RATE * 16); // Calculate _divisor for baudrate + TEMP_REG_VAL = 0x08; // UART Software reset + UART_WriteRegister(REG_IOCONTROL, TEMP_REG_VAL); + TEMP_REG_VAL = 0x00; // Set pins to GPIO mode + UART_WriteRegister(REG_IOCONTROL, TEMP_REG_VAL); + TEMP_REG_VAL = 0xFF; //Set all pins as output + UART_WriteRegister(REG_IODIR, TEMP_REG_VAL); + UART_ReadRegister(REG_IOSTATE); // Read current state as not to overwrite the other GPIO pins + TEMP_REG_VAL = _inbuffer[0]; + setGPIO(); // Set the audio mixer channel + /* + if (_UART_CH == 0){ // Set Audio mixer channel + TEMP_REG_VAL |= (0x01 << _UART_CH); //Set GPIO pin 0 to high + } else { // must be UART 1 + TEMP_REG_VAL |= (0x01 << _UART_CH); //Set GPIO pin 1 to high + } + UART_WriteRegister(REG_IOSTATE, TEMP_REG_VAL); + */ + TEMP_REG_VAL = 0x07; // Reset FIFO, clear RX & TX FIFO + UART_WriteRegister(REG_FCR, TEMP_REG_VAL); + TEMP_REG_VAL = 0x00; // Set MCR to all 0, includes Clock divisor + UART_WriteRegister(REG_MCR, TEMP_REG_VAL); + TEMP_REG_VAL = 0x80 | WORD_LEN | STOP_BIT | PARITY_ENA | PARITY_TYPE; + UART_WriteRegister(REG_LCR, TEMP_REG_VAL); // Divisor latch enabled + UART_WriteRegister(REG_DLL, (uint8_t)_divisor); // Write DLL + UART_WriteRegister(REG_DLH, (uint8_t)(_divisor >> 8)); // Write DLH + UART_ReadRegister(REG_LCR); + TEMP_REG_VAL = _inbuffer[0] & 0x7F; // Disable Divisor latch enabled bit + UART_WriteRegister(REG_LCR, TEMP_REG_VAL); // Divisor latch disabled + + uint8_t status = _rb.status; + if (status != I2C_STATUS_OK) { + DIAG(F("SC16IS752: I2C: %s failed %S"), _I2CAddress.toString(), I2CManager.getErrorMessage(status)); + _deviceState = DEVSTATE_FAILED; + } else { + #ifdef DIAG_IO + DIAG(F("SC16IS752: I2C: %s, _deviceState: %S"), _I2CAddress.toString(), I2CManager.getErrorMessage(status)); + #endif + _deviceState = DEVSTATE_NORMAL; // If I2C state is OK, then proceed to initialize DFPlayer + } + } + + + // Read the Receive FIFO Level register (RXLVL), return a single unsigned integer + // of nr of characters in the RX FIFO, bit 6:0, 7 not used, set to zero + // value from 0 (0x00) to 64 (0x40) Only display if RX FIFO has data + // The RX fifo level is used to check if there are enough bytes to process a frame + void RX_fifo_lvl(){ + UART_ReadRegister(REG_RXLV); + FIFO_RX_LEVEL = _inbuffer[0]; + #ifdef DIAG_I2CDFplayer + if (FIFO_RX_LEVEL > 0){ + //if (FIFO_RX_LEVEL > 0 && FIFO_RX_LEVEL < 10){ + DIAG(F("SC16IS752: At I2C: %s, UART channel: 0x%x, FIFO_RX_LEVEL: 0d%d"), _I2CAddress.toString(), _UART_CH, _inbuffer[0]); + } + #endif + } + + // When a frame is transmitted from the DFPlayer to the serial port, and at the same time the CS is sending a 42 query + // the following two frames from the DFPlayer are corrupt. This result in the receive buffer being out of sync and the + // CS will complain and generate a timeout. + // The RX fifo has corrupt data and need to be flushed, this function does that + // + void resetRX_fifo(){ + #ifdef DIAG_I2CDFplayer + DIAG(F("SC16IS752: At I2C: %s, UART channel: 0x%x, RX fifo reset"), _I2CAddress.toString(), _UART_CH); + #endif + TEMP_REG_VAL = 0x03; // Reset RX fifo + UART_WriteRegister(REG_FCR, TEMP_REG_VAL); + } + + // Set or reset GPIO pin 0 and 1 depending on the UART ch + // This function may be modified in a future release to enable all 8 pins to be set or reset with EX-Rail + // for various auxilary functions + void setGPIO(){ + UART_ReadRegister(REG_IOSTATE); // Get the current GPIO pins state from the IOSTATE register + TEMP_REG_VAL = _inbuffer[0]; + if (_audioMixer == 1){ // set to audio mixer 1 + if (_UART_CH == 0){ + TEMP_REG_VAL |= (0x01 << _UART_CH); //Set GPIO pin 0 to high + } else { // must be UART 1 + TEMP_REG_VAL |= (0x01 << _UART_CH); //Set GPIO pin 1 to high + } + } else { // set to audio mixer 2 + if (_UART_CH == 0){ + TEMP_REG_VAL &= ~(0x01 << _UART_CH); //Set GPIO pin 0 to Low + } else { // must be UART 1 + TEMP_REG_VAL &= ~(0x01 << _UART_CH); //Set GPIO pin 1 to Low + } + } + UART_WriteRegister(REG_IOSTATE, TEMP_REG_VAL); + _setamCmd = false; + } + + + // Read the Tranmit FIFO Level register (TXLVL), return a single unsigned integer + // of nr characters free in the TX FIFO, bit 6:0, 7 not used, set to zero + // value from 0 (0x00) to 64 (0x40) + // + void TX_fifo_lvl(){ + UART_ReadRegister(REG_TXLV); + FIFO_TX_LEVEL = _inbuffer[0]; + #ifdef DIAG_I2CDFplayer + // DIAG(F("SC16IS752: At I2C: %s, UART channel: 0x%x, FIFO_TX_LEVEL: 0d%d"), _I2CAddress.toString(), _UART_CH, FIFO_TX_LEVEL); + #endif + } + + + //void UART_WriteRegister(I2CAddress _I2CAddress, uint8_t _UART_CH, uint8_t UART_REG, uint8_t Val, I2CRB &_rb){ + void UART_WriteRegister(uint8_t UART_REG, uint8_t Val){ + _outbuffer[0] = UART_REG << 3 | _UART_CH << 1; + _outbuffer[1] = Val; + #ifdef DIAG_I2CDFplayer_reg + DIAG(F("SC16IS752: Write register at I2C: %s, UART channel: 0x%x, Register: 0x%x, Data: 0b%b"), _I2CAddress.toString(), _UART_CH, UART_REG, _outbuffer[1]); + #endif + I2CManager.write(_I2CAddress, _outbuffer, 2); + } + + + void UART_ReadRegister(uint8_t UART_REG){ + _outbuffer[0] = UART_REG << 3 | _UART_CH << 1; // _outbuffer[0] has now UART_REG and UART_CH + I2CManager.read(_I2CAddress, _inbuffer, 1, _outbuffer, 1); + // _inbuffer has the REG data + #ifdef DIAG_I2CDFplayer_reg + DIAG(F("SC16IS752: Read register at I2C: %s, UART channel: 0x%x, Register: 0x%x, Data: 0b%b"), _I2CAddress.toString(), _UART_CH, UART_REG, _inbuffer[0]); + #endif + } + +// SC16IS752 General register set (from the datasheet) +enum : uint8_t{ + REG_RHR = 0x00, // FIFO Read + REG_THR = 0x00, // FIFO Write + REG_IER = 0x01, // Interrupt Enable Register R/W + REG_FCR = 0x02, // FIFO Control Register Write + REG_IIR = 0x02, // Interrupt Identification Register Read + REG_LCR = 0x03, // Line Control Register R/W + REG_MCR = 0x04, // Modem Control Register R/W + REG_LSR = 0x05, // Line Status Register Read + REG_MSR = 0x06, // Modem Status Register Read + REG_SPR = 0x07, // Scratchpad Register R/W + REG_TCR = 0x06, // Transmission Control Register R/W + REG_TLR = 0x07, // Trigger Level Register R/W + REG_TXLV = 0x08, // Transmitter FIFO Level register Read + REG_RXLV = 0x09, // Receiver FIFO Level register Read + REG_IODIR = 0x0A, // Programmable I/O pins Direction register R/W + REG_IOSTATE = 0x0B, // Programmable I/O pins State register R/W + REG_IOINTENA = 0x0C, // I/O Interrupt Enable register R/W + REG_IOCONTROL = 0x0E, // I/O Control register R/W + REG_EFCR = 0x0F, // Extra Features Control Register R/W + }; + +// SC16IS752 Special register set +enum : uint8_t{ + REG_DLL = 0x00, // Division registers R/W + REG_DLH = 0x01, // Division registers R/W + }; + +// SC16IS752 Enhanced regiter set +enum : uint8_t{ + REG_EFR = 0X02, // Enhanced Features Register R/W + REG_XON1 = 0x04, // R/W + REG_XON2 = 0x05, // R/W + REG_XOFF1 = 0x06, // R/W + REG_XOFF2 = 0x07, // R/W + }; + +// DFPlayer commands and values +enum : uint8_t{ + PLAY = 0x0F, + VOL = 0x06, + FOLDER = 0x2B, // Not a DFPlayer command, used to set folder nr where audio file is + REPEATPLAY = 0x08, + STOPPLAY = 0x16, + EQ = 0x07, // Set equaliser, require parameter NORMAL, POP, ROCK, JAZZ, CLASSIC or BASS + RESET = 0x0C, + DACON = 0x1A, + SETAM = 0x2A, // Set audio mixer 1 or 2 for this DFPLayer + NORMAL = 0x00, // Equalizer parameters + POP = 0x01, + ROCK = 0x02, + JAZZ = 0x03, + CLASSIC = 0x04, + BASS = 0x05, + }; + +}; + +#endif // IO_I2CDFPlayer_h diff --git a/version.h b/version.h index e94303f..d44166a 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,11 @@ #include "StringFormatter.h" -#define VERSION "5.2.28" +#define VERSION "5.2.29" +// 5.2.29 - Added IO_I2CDFPlayer.h to support DFPLayer over I2C connected to NXP SC16IS750/SC16IS752 (currently only single UART for SC16IS752) +// - Added enhanced IO_I2CDFPLayer enum commands to EXRAIL2.h +// - Added PLAYSOUND alias of ANOUT to EXRAILMacros.h +// - Added UART detection to I2CManager.cpp // 5.2.28 - ESP32: Can all Wifi channels. // - ESP32: Only write Wifi password to display if it is a well known one // 5.2.27 - Bugfix: IOExpander memory allocation From 7cbf4de1b977c2e0aea65a32da3a53dc5a2c0781 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 3 Feb 2024 19:25:41 +0000 Subject: [PATCH 29/54] Update myHal.cpp_example.txt Update with instructions for IO_ I2CDFPlayer --- myHal.cpp_example.txt | 28 ++++++++++++++++++++++++++++ 1 file changed, 28 insertions(+) diff --git a/myHal.cpp_example.txt b/myHal.cpp_example.txt index 5533554..8f97290 100644 --- a/myHal.cpp_example.txt +++ b/myHal.cpp_example.txt @@ -25,6 +25,7 @@ //#include "IO_EXTurntable.h" // Turntable-EX turntable controller //#include "IO_EXFastClock.h" // FastClock driver //#include "IO_PCA9555.h" // 16-bit I/O expander (NXP & Texas Instruments). +//#include "IO_I2CDFPlayer.h" // DFPlayer over I2C //========================================================================== // The function halSetup() is invoked from CS if it exists within the build. @@ -234,6 +235,33 @@ void halSetup() { // DFPlayer::create(10000, 10, Serial1); + //======================================================================= + // Play mp3 files from a Micro-SD card, using a DFPlayer MP3 Module on a SC16IS750/SC16IS752 I2C UART + //======================================================================= + // DFPlayer via NXP SC16IS752 I2C Dual UART. Each device has 2 UARTs on a single I2C address + // Total nr of devices on an I2C bus is 16, with 2 UARTs on each address making a total of 32 UARTs per I2C bus + // I2C address range 0x48 - 0x57 + // + // audioMixer can be 1 when connected to audio mixer 1, 2 when connected to audio mixer 2, 0 will default to 1 + // Generic format: + // I2CDFPlayer::create(1st vPin, vPins, I2C address, xtal); + // Parameters: + // 1st vPin : First virtual pin that EX-Rail can control to play a sound, use PLAYSOUND command (alias of ANOUT) + // vPins : Total number of virtual pins allocated (1 vPin is supported currently) + // 1st vPin for UART 0 + // I2C Address : I2C address of the serial controller, in 0x format + // xtal : 0 for 1.8432Mhz, 1 for 14.7456Mhz + // + // The vPin is also a pin that can be read with the WAITFOR(vPin) command indicating if the DFPlayer has finished playing a track + // + + // I2CDFPlayer::create(10000, 1, 0x48, 1); + // + // Configuration example on a multiplexer + // I2CDFPlayer::create(10000, 1, {I2CMux_0, SubBus_0, 0x48}, 1); + + + //======================================================================= // 16-pad capacitative touch key pad based on TP229 IC. //======================================================================= From 63702ae64e1d1c9bb3ae0ccab3648edfc51c54ce Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 3 Feb 2024 19:27:58 +0000 Subject: [PATCH 30/54] Update fro myHal.cpp_example.txt Noticed some ommissions, corrected now --- myHal.cpp_example.txt | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/myHal.cpp_example.txt b/myHal.cpp_example.txt index 8f97290..9073430 100644 --- a/myHal.cpp_example.txt +++ b/myHal.cpp_example.txt @@ -238,11 +238,9 @@ void halSetup() { //======================================================================= // Play mp3 files from a Micro-SD card, using a DFPlayer MP3 Module on a SC16IS750/SC16IS752 I2C UART //======================================================================= - // DFPlayer via NXP SC16IS752 I2C Dual UART. Each device has 2 UARTs on a single I2C address - // Total nr of devices on an I2C bus is 16, with 2 UARTs on each address making a total of 32 UARTs per I2C bus + // DFPlayer via NXP SC16IS752 I2C Dual UART. // I2C address range 0x48 - 0x57 // - // audioMixer can be 1 when connected to audio mixer 1, 2 when connected to audio mixer 2, 0 will default to 1 // Generic format: // I2CDFPlayer::create(1st vPin, vPins, I2C address, xtal); // Parameters: From e7f82bdf9269245e80e31cdbb4342440a9c4bf7f Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 4 Feb 2024 12:44:16 +0100 Subject: [PATCH 31/54] WiThrottle sendIntro after initial N message as well --- WiThrottle.cpp | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/WiThrottle.cpp b/WiThrottle.cpp index 244dfd8..018ab2b 100644 --- a/WiThrottle.cpp +++ b/WiThrottle.cpp @@ -187,6 +187,7 @@ void WiThrottle::parse(RingStream * stream, byte * cmdx) { } break; case 'N': // Heartbeat (2), only send if connection completed by 'HU' message + sendIntro(stream); StringFormatter::send(stream, F("*%d\n"), heartrateSent ? HEARTBEAT_SECONDS : HEARTBEAT_PRELOAD); // return timeout value break; case 'M': // multithrottle @@ -194,7 +195,7 @@ void WiThrottle::parse(RingStream * stream, byte * cmdx) { break; case 'H': // send initial connection info after receiving "HU" message if (cmd[1] == 'U') { - sendIntro(stream); + sendIntro(stream); } break; case 'Q': // @@ -498,12 +499,14 @@ void WiThrottle::getLocoCallback(int16_t locoid) { } void WiThrottle::sendIntro(Print* stream) { + if (introSent) // sendIntro only once + return; introSent=true; StringFormatter::send(stream,F("VN2.0\nHTDCC-EX\nRL0\n")); - StringFormatter::send(stream,F("HtDCC-EX v%S, %S, %S, %S\n"), F(VERSION), F(ARDUINO_TYPE), DCC::getMotorShieldName(), F(GITHUB_SHA)); - StringFormatter::send(stream,F("PTT]\\[Turnouts}|{Turnout]\\[THROW}|{2]\\[CLOSE}|{4\n")); - StringFormatter::send(stream,F("PPA%x\n"),TrackManager::getMainPower()==POWERMODE::ON); - // set heartbeat to 2 seconds because we need to sync the metadata (1 second is too short!) + StringFormatter::send(stream,F("HtDCC-EX v%S, %S, %S, %S\n"), F(VERSION), F(ARDUINO_TYPE), DCC::getMotorShieldName(), F(GITHUB_SHA)); + StringFormatter::send(stream,F("PTT]\\[Turnouts}|{Turnout]\\[THROW}|{2]\\[CLOSE}|{4\n")); + StringFormatter::send(stream,F("PPA%x\n"),TrackManager::getMainPower()==POWERMODE::ON); + // set heartbeat to 2 seconds because we need to sync the metadata (1 second is too short!) StringFormatter::send(stream,F("*%d\nHMConnecting..\n"), HEARTBEAT_PRELOAD); } From be40a7e274cd7eb907ca2fd75e26f2c707f885fd Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 4 Feb 2024 12:51:41 +0100 Subject: [PATCH 32/54] version 5.2.30 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 8aa2bd8..56992fe 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401212011Z" +#define GITHUB_SHA "devel-202402041151Z" diff --git a/version.h b/version.h index d44166a..c443179 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.29" +#define VERSION "5.2.30" +// 5.2.40 - Bugfix: WiThrottle sendIntro after initial N message as well // 5.2.29 - Added IO_I2CDFPlayer.h to support DFPLayer over I2C connected to NXP SC16IS750/SC16IS752 (currently only single UART for SC16IS752) // - Added enhanced IO_I2CDFPLayer enum commands to EXRAIL2.h // - Added PLAYSOUND alias of ANOUT to EXRAILMacros.h From 5f6e18e1e78620ea77a9b3bfe9e1d9dc740a5b8d Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 4 Feb 2024 13:50:07 +0100 Subject: [PATCH 33/54] remove mega328 from default build env list --- platformio.ini | 1 - 1 file changed, 1 deletion(-) diff --git a/platformio.ini b/platformio.ini index 8767ef1..2630e6d 100644 --- a/platformio.ini +++ b/platformio.ini @@ -12,7 +12,6 @@ default_envs = mega2560 uno - mega328 unowifiR2 nano samd21-dev-usb From 4780ea63cf48ca544e3d9bfd3c285ee283aca5fc Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sun, 4 Feb 2024 18:57:30 +0000 Subject: [PATCH 34/54] Prepend I2CDFPlayer with DF_ to solve Nucleo RESET directive Prepend all I2CDFPlayer EXRail commands with DF_ to solve a Nucleo defined RESET --- EXRAIL2.h | 30 +++++++++++++------------- IO_I2CDFPlayer.h | 56 +++++++++++++++++++++++++----------------------- 2 files changed, 44 insertions(+), 42 deletions(-) diff --git a/EXRAIL2.h b/EXRAIL2.h index 6652526..ccfbbe6 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -260,21 +260,21 @@ private: // IO_I2CDFPlayer commands and values enum : uint8_t{ - PLAY = 0x0F, - VOL = 0x06, - FOLDER = 0x2B, // Not a DFPlayer command, used to set folder nr where audio file is - REPEATPLAY = 0x08, - STOPPLAY = 0x16, - EQ = 0x07, // Set equaliser, require parameter NORMAL, POP, ROCK, JAZZ, CLASSIC or BASS - RESET = 0x0C, - DACON = 0x1A, - SETAM = 0x2A, // Set audio mixer 1 or 2 for this DFPLayer (future use) - NORMAL = 0x00, // Equalizer parameters - POP = 0x01, - ROCK = 0x02, - JAZZ = 0x03, - CLASSIC = 0x04, - BASS = 0x05, + DF_PLAY = 0x0F, + DF_VOL = 0x06, + DF_FOLDER = 0x2B, // Not a DFPlayer command, used to set folder nr where audio file is + DF_REPEATPLAY = 0x08, + DF_STOPPLAY = 0x16, + DF_EQ = 0x07, // Set equaliser, require parameter NORMAL, POP, ROCK, JAZZ, CLASSIC or BASS + DF_RESET = 0x0C, + DF_DACON = 0x1A, + DF_SETAM = 0x2A, // Set audio mixer 1 or 2 for this DFPLayer + DF_NORMAL = 0x00, // Equalizer parameters + DF_POP = 0x01, + DF_ROCK = 0x02, + DF_JAZZ = 0x03, + DF_CLASSIC = 0x04, + DF_BASS = 0x05, }; #endif diff --git a/IO_I2CDFPlayer.h b/IO_I2CDFPlayer.h index 79fa16b..c291b56 100644 --- a/IO_I2CDFPlayer.h +++ b/IO_I2CDFPlayer.h @@ -101,8 +101,8 @@ private: bool _stopplayCmd = false; bool _resetCmd = false; bool _eqCmd = false; - uint8_t _requestedEQValue = NORMAL; - uint8_t _currentEQvalue = NORMAL; // start equalizer value + uint8_t _requestedEQValue = DF_NORMAL; + uint8_t _currentEQvalue = DF_NORMAL; // start equalizer value bool _daconCmd = false; uint8_t _audioMixer = 0x01; // Default to output amplifier 1 bool _setamCmd = false; // Set the Audio mixer channel @@ -434,18 +434,18 @@ public: //case NONE: // DFPlayerCmd = cmd; // break; - case PLAY: + case DF_PLAY: _playCmd = true; _volCmd = true; _requestedSong = value; _requestedVolumeLevel = volume; _playing = true; break; - case VOL: + case DF_VOL: _volCmd = true; _requestedVolumeLevel = volume; break; - case FOLDER: + case DF_FOLDER: _folderCmd = true; if (volume <= 0 || volume > 99){ // Range checking, valid values 1-99, else default to 1 _requestedFolder = 0x01; // if outside range, default to folder 01 @@ -453,7 +453,7 @@ public: _requestedFolder = volume; } break; - case REPEATPLAY: // Need to check if _repeat == true, if so do nothing + case DF_REPEATPLAY: // Need to check if _repeat == true, if so do nothing if (_repeat == false) { #ifdef DIAG_I2CDFplayer_playing DIAG(F("I2CDFPlayer: WriteAnalog Repeat: _repeat: 0x0%x, value: %d _repeatCmd: 0x%x"), _repeat, value, _repeatCmd); @@ -464,30 +464,30 @@ public: _playing = true; } break; - case STOPPLAY: + case DF_STOPPLAY: _stopplayCmd = true; break; - case EQ: + case DF_EQ: #ifdef DIAG_I2CDFplayer_playing DIAG(F("I2CDFPlayer: WriteAnalog EQ: cmd: 0x%x, EQ value: 0x%x"), cmd, volume); #endif _eqCmd = true; if (volume <= 0 || volume > 5) { // If out of range, default to NORMAL - _requestedEQValue = NORMAL; + _requestedEQValue = DF_NORMAL; } else { // Valid EQ parameter range _requestedEQValue = volume; } break; - case RESET: + case DF_RESET: _resetCmd = true; break; - case DACON: // Works, but without the DACOFF command limited value, except when not relying on DFPlayer default to turn the DAC on + case DF_DACON: // Works, but without the DACOFF command limited value, except when not relying on DFPlayer default to turn the DAC on #ifdef DIAG_I2CDFplayer_playing DIAG(F("I2CDFPlayer: WrtieAnalog DACON: cmd: 0x%x"), cmd); #endif _daconCmd = true; break; - case SETAM: // Set the audio mixer channel to 1 or 2 + case DF_SETAM: // Set the audio mixer channel to 1 or 2 _setamCmd = true; #ifdef DIAG_I2CDFplayer_playing DIAG(F("I2CDFPlayer: WrtieAnalog SETAM: cmd: 0x%x"), cmd); @@ -779,23 +779,25 @@ enum : uint8_t{ REG_XOFF2 = 0x07, // R/W }; + // DFPlayer commands and values +// Declared in this scope enum : uint8_t{ - PLAY = 0x0F, - VOL = 0x06, - FOLDER = 0x2B, // Not a DFPlayer command, used to set folder nr where audio file is - REPEATPLAY = 0x08, - STOPPLAY = 0x16, - EQ = 0x07, // Set equaliser, require parameter NORMAL, POP, ROCK, JAZZ, CLASSIC or BASS - RESET = 0x0C, - DACON = 0x1A, - SETAM = 0x2A, // Set audio mixer 1 or 2 for this DFPLayer - NORMAL = 0x00, // Equalizer parameters - POP = 0x01, - ROCK = 0x02, - JAZZ = 0x03, - CLASSIC = 0x04, - BASS = 0x05, + DF_PLAY = 0x0F, + DF_VOL = 0x06, + DF_FOLDER = 0x2B, // Not a DFPlayer command, used to set folder nr where audio file is + DF_REPEATPLAY = 0x08, + DF_STOPPLAY = 0x16, + DF_EQ = 0x07, // Set equaliser, require parameter NORMAL, POP, ROCK, JAZZ, CLASSIC or BASS + DF_RESET = 0x0C, + DF_DACON = 0x1A, + DF_SETAM = 0x2A, // Set audio mixer 1 or 2 for this DFPLayer + DF_NORMAL = 0x00, // Equalizer parameters + DF_POP = 0x01, + DF_ROCK = 0x02, + DF_JAZZ = 0x03, + DF_CLASSIC = 0x04, + DF_BASS = 0x05, }; }; From 4931c5ed75af7466d205c3e8fe5e07cdadfa390f Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 5 Feb 2024 09:28:07 +0100 Subject: [PATCH 35/54] tag --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 56992fe..956a8d2 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202402041151Z" +#define GITHUB_SHA "devel-202402050827Z" From cd47782052aaae9ae378aa3d9f32c86bc36c182f Mon Sep 17 00:00:00 2001 From: Asbelos Date: Tue, 6 Feb 2024 20:03:52 +0000 Subject: [PATCH 36/54] reasonable start --- DCCEXParser.cpp | 8 +++++++- DCCTimer.h | 2 ++ DCCTimerAVR.cpp | 50 ++++++++++++++++++++++++++++++++++++++++++++++++ DCCWaveform.cpp | 27 ++++++++++++++++++++++---- DCCWaveform.h | 13 ++++++++++++- MotorDriver.cpp | 2 +- TrackManager.cpp | 5 ++--- 7 files changed, 97 insertions(+), 10 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 16f4494..3f61f7b 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1035,7 +1035,13 @@ bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) { DCC::setGlobalSpeedsteps(128); DIAG(F("128 Speedsteps")); return true; - + case "RAILCOM"_hk: + { + bool onOff = (params > 1) && (p[1] == 1 || p[1] == "ON"_hk); // dont care if other stuff or missing... just means off + DIAG(F("Railcom %S") + ,DCCWaveform::setRailcom(onOff)?F("ON"):F("OFF")); + return true; + } #ifndef DISABLE_PROG case "ACK"_hk: // if (params >= 3) { diff --git a/DCCTimer.h b/DCCTimer.h index 3b14fd6..11e1c7f 100644 --- a/DCCTimer.h +++ b/DCCTimer.h @@ -62,6 +62,8 @@ class DCCTimer { static bool isPWMPin(byte pin); static void setPWM(byte pin, bool high); static void clearPWM(); + static void startRailcomTimer(byte brakePin); + static void ackRailcomTimer(); static void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency); static void DCCEXanalogWrite(uint8_t pin, int value); diff --git a/DCCTimerAVR.cpp b/DCCTimerAVR.cpp index 3e6c436..ea601df 100644 --- a/DCCTimerAVR.cpp +++ b/DCCTimerAVR.cpp @@ -39,6 +39,9 @@ INTERRUPT_CALLBACK interruptHandler=0; #define TIMER1_A_PIN 11 #define TIMER1_B_PIN 12 #define TIMER1_C_PIN 13 + #define TIMER2_A_PIN 10 + #define TIMER2_B_PIN 9 + #else #define TIMER1_A_PIN 9 #define TIMER1_B_PIN 10 @@ -55,6 +58,53 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { interrupts(); } + +void DCCTimer::startRailcomTimer(byte brakePin) { + /* The Railcom timer is started in such a way that it + - First triggers 28uS after the last TIMER1 tick. + This provides an accurate offset (in High Accuracy mode) + for the start of the Railcom cutout. + - Sets the Railcom pin high at first tick, + because its been setup with 100% PWM duty cycle. + + - Cycles at 436uS so the second tick is the + correct distance from the cutout. + + - Waveform code is responsible for altering the PWM + duty cycle to 0% any time between the first and last tick. + (there will be 7 DCC timer1 ticks in which to do this.) + + */ + const int cutoutDuration = 436; // Desired interval in microseconds + + // Set up Timer2 for CTC mode (Clear Timer on Compare Match) + TCCR2A = 0; // Clear Timer2 control register A + TCCR2B = 0; // Clear Timer2 control register B + TCNT2 = 0; // Initialize Timer2 counter value to 0 + // Configure Phase and Frequency Correct PWM mode +//TCCR2A = (1 << COM2B1) | (1 << WGM20) | (1 << WGM21); + + // Set Fast PWM mode with non-inverted output on OC2B (pin 9) + TCCR2A = (1 << WGM21) | (1 << WGM20) | (1 << COM2B1); + // Set Timer 2 prescaler to 32 + TCCR2B = (1 << CS21) | (1 << CS20); // 32 prescaler + + // Set the compare match value for desired interval + OCR2A = (F_CPU / 1000000) * cutoutDuration / 32 - 1; + + // Calculate the compare match value for desired duty cycle + OCR2B = OCR2A+1; // set duty cycle to 100%= OCR2A) + + // Enable Timer2 output on pin 9 (OC2B) + DDRB |= (1 << DDB1); + // TODO Fudge TCNT2 to sync with last tcnt1 tick + 28uS +} + +void DCCTimer::ackRailcomTimer() { + OCR2B= 0x00; // brfake pin pwm duty cycle 0 at next tick +} + + // ISR called by timer interrupt every 58uS ISR(TIMER1_OVF_vect){ interruptHandler(); } diff --git a/DCCWaveform.cpp b/DCCWaveform.cpp index 93b21a2..707f8f4 100644 --- a/DCCWaveform.cpp +++ b/DCCWaveform.cpp @@ -115,8 +115,19 @@ DCCWaveform::DCCWaveform( byte preambleBits, bool isMain) { bytes_sent = 0; bits_sent = 0; } + +volatile bool DCCWaveform::railcomActive=false; // switched on by user - +bool DCCWaveform::setRailcom(bool on) { + if (on) { + // TODO check possible + railcomActive=true; + } + else { + railcomActive=false; + } + return railcomActive; +} #pragma GCC push_options #pragma GCC optimize ("-O3") @@ -124,16 +135,16 @@ void DCCWaveform::interrupt2() { // calculate the next bit to be sent: // set state WAVE_MID_1 for a 1=bit // or WAVE_HIGH_0 for a 0 bit. - if (remainingPreambles > 0 ) { state=WAVE_MID_1; // switch state to trigger LOW on next interrupt remainingPreambles--; - + // As we get to the end of the preambles, open the reminder window. // This delays any reminder insertion until the last moment so // that the reminder doesn't block a more urgent packet. reminderWindowOpen=transmitRepeats==0 && remainingPreambles<4 && remainingPreambles>1; if (remainingPreambles==1) promotePendingPacket(); + else if (remainingPreambles==10 && isMainTrack && railcomActive) DCCTimer::ackRailcomTimer(); // Update free memory diagnostic as we don't have anything else to do this time. // Allow for checkAck and its called functions using 22 bytes more. else DCCTimer::updateMinimumFreeMemoryISR(22); @@ -157,6 +168,12 @@ void DCCWaveform::interrupt2() { bytes_sent = 0; // preamble for next packet will start... remainingPreambles = requiredPreambles; + + // set the railcom coundown to trigger half way + // through the first preamble bit. + // Note.. we are still sending the last packet bit + // and we then have to allow for the packet end bit + if (isMainTrack && railcomActive) DCCTimer::startRailcomTimer(9); } } } @@ -208,7 +225,9 @@ void DCCWaveform::promotePendingPacket() { // nothing to do, just send idles or resets // Fortunately reset and idle packets are the same length - memcpy( transmitPacket, isMainTrack ? idlePacket : resetPacket, sizeof(idlePacket)); + // TEMPORARY DEBUG FOR RAILCOM + // memcpy( transmitPacket, isMainTrack ? idlePacket : resetPacket, sizeof(idlePacket)); + memcpy( transmitPacket, resetPacket, sizeof(idlePacket)); transmitLength = sizeof(idlePacket); transmitRepeats = 0; if (getResets() < 250) sentResetsSincePacket++; // only place to increment (private!) diff --git a/DCCWaveform.h b/DCCWaveform.h index 1392288..3f6de18 100644 --- a/DCCWaveform.h +++ b/DCCWaveform.h @@ -40,7 +40,14 @@ const byte MAX_PACKET_SIZE = 5; // NMRA standard extended packets, payload s // The WAVE_STATE enum is deliberately numbered because a change of order would be catastrophic // to the transform array. -enum WAVE_STATE : byte {WAVE_START=0,WAVE_MID_1=1,WAVE_HIGH_0=2,WAVE_MID_0=3,WAVE_LOW_0=4,WAVE_PENDING=5}; +enum WAVE_STATE : byte { + WAVE_START=0, // wave going high at start of bit + WAVE_MID_1=1, // middle of 1 bit + WAVE_HIGH_0=2, // first part of 0 bit high + WAVE_MID_0=3, // middle of 0 bit + WAVE_LOW_0=4, // first part of 0 bit low + WAVE_PENDING=5 // next bit not yet known + }; // NOTE: static functions are used for the overall controller, then // one instance is created for each track. @@ -78,6 +85,8 @@ class DCCWaveform { void schedulePacket(const byte buffer[], byte byteCount, byte repeats); bool isReminderWindowOpen(); void promotePendingPacket(); + static bool setRailcom(bool on); + static bool isRailcom() {return railcomActive;} private: #ifndef ARDUINO_ARCH_ESP32 @@ -103,6 +112,8 @@ class DCCWaveform { byte pendingPacket[MAX_PACKET_SIZE+1]; // +1 for checksum byte pendingLength; byte pendingRepeats; + static volatile bool railcomActive; // switched on by user + #ifdef ARDUINO_ARCH_ESP32 static RMTChannel *rmtMainChannel; static RMTChannel *rmtProgChannel; diff --git a/MotorDriver.cpp b/MotorDriver.cpp index bd25be4..878beea 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -204,7 +204,7 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i } bool MotorDriver::isPWMCapable() { - return (!dualSignal) && DCCTimer::isPWMPin(signalPin); + return (!dualSignal) && DCCTimer::isPWMPin(signalPin); } diff --git a/TrackManager.cpp b/TrackManager.cpp index da96832..328f952 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -157,10 +157,9 @@ void TrackManager::setDCCSignal( bool on) { HAVE_PORTF(PORTF=shadowPORTF); } +// Called by interrupt context void TrackManager::setCutout( bool on) { - (void) on; - // TODO Cutout needs fake ports as well - // TODO APPLY_BY_MODE(TRACK_MODE_MAIN,setCutout(on)); + APPLY_BY_MODE(TRACK_MODE_MAIN,setBrake(on,true)); } // setPROGSignal(), called from interrupt context From 1443ea8df95dcdead26dd9060424ce58ba7f6888 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 7 Feb 2024 19:50:08 +0000 Subject: [PATCH 37/54] Its alive! --- DCCTimerAVR.cpp | 25 +++++++++++++++++++------ 1 file changed, 19 insertions(+), 6 deletions(-) diff --git a/DCCTimerAVR.cpp b/DCCTimerAVR.cpp index ea601df..66b51ba 100644 --- a/DCCTimerAVR.cpp +++ b/DCCTimerAVR.cpp @@ -75,22 +75,22 @@ void DCCTimer::startRailcomTimer(byte brakePin) { (there will be 7 DCC timer1 ticks in which to do this.) */ - const int cutoutDuration = 436; // Desired interval in microseconds + const int cutoutDuration = 430; // Desired interval in microseconds // Set up Timer2 for CTC mode (Clear Timer on Compare Match) TCCR2A = 0; // Clear Timer2 control register A TCCR2B = 0; // Clear Timer2 control register B TCNT2 = 0; // Initialize Timer2 counter value to 0 // Configure Phase and Frequency Correct PWM mode -//TCCR2A = (1 << COM2B1) | (1 << WGM20) | (1 << WGM21); + TCCR2A = (1 << COM2B1); // enable pwm on pin 9 + TCCR2A |= (1 << WGM20); - // Set Fast PWM mode with non-inverted output on OC2B (pin 9) - TCCR2A = (1 << WGM21) | (1 << WGM20) | (1 << COM2B1); + // Set Timer 2 prescaler to 32 TCCR2B = (1 << CS21) | (1 << CS20); // 32 prescaler // Set the compare match value for desired interval - OCR2A = (F_CPU / 1000000) * cutoutDuration / 32 - 1; + OCR2A = (F_CPU / 1000000) * cutoutDuration / 64 - 1; // Calculate the compare match value for desired duty cycle OCR2B = OCR2A+1; // set duty cycle to 100%= OCR2A) @@ -98,10 +98,23 @@ void DCCTimer::startRailcomTimer(byte brakePin) { // Enable Timer2 output on pin 9 (OC2B) DDRB |= (1 << DDB1); // TODO Fudge TCNT2 to sync with last tcnt1 tick + 28uS + + // Previous TIMER1 Tick was at rising end-of-packet bit + // Cutout starts half way through first preamble + // that is 2.5 * 58uS later. + // TCNT1 ticks 8 times / microsecond + // auto microsendsToFirstRailcomTick=(58+58+29)-(TCNT1/8); + // set the railcom timer counter allowing for phase-correct + + // CHris's NOTE: + // I dont kniow quite how this calculation works out but + // it does seems to get a good answer. + + TCNT2=193 + (ICR1 - TCNT1)/8; } void DCCTimer::ackRailcomTimer() { - OCR2B= 0x00; // brfake pin pwm duty cycle 0 at next tick + OCR2B= 0x00; // brake pin pwm duty cycle 0 at next tick } From 7a9e225602247a5f6a433f8b1c88976bcca0d0e0 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 7 Feb 2024 21:24:48 +0000 Subject: [PATCH 38/54] fill in debug and unsupported drivers --- DCCEXParser.cpp | 23 ++++++++++++++++++++--- DCCTimerMEGAAVR.cpp | 8 ++++++++ DCCTimerSAMD.cpp | 8 ++++++++ DCCTimerSTM32.cpp | 8 ++++++++ DCCTimerTEENSY.cpp | 8 ++++++++ DCCWaveform.cpp | 19 +++++++++++++++---- DCCWaveform.h | 3 ++- 7 files changed, 69 insertions(+), 8 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 3f61f7b..5b335d2 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1036,10 +1036,27 @@ bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) { DIAG(F("128 Speedsteps")); return true; case "RAILCOM"_hk: - { - bool onOff = (params > 1) && (p[1] == 1 || p[1] == "ON"_hk); // dont care if other stuff or missing... just means off + { // + if (params<2) return false; + bool on=false; + bool debug=false; + switch (p[1]) { + case "ON"_hk: + case 1: + on=true; + break; + case "DEBUG"_hk: + on=true; + debug=true; + break; + case "OFF"_hk: + case 0: + break; + default: + return false; + } DIAG(F("Railcom %S") - ,DCCWaveform::setRailcom(onOff)?F("ON"):F("OFF")); + ,DCCWaveform::setRailcom(on,debug)?F("ON"):F("OFF")); return true; } #ifndef DISABLE_PROG diff --git a/DCCTimerMEGAAVR.cpp b/DCCTimerMEGAAVR.cpp index 2b2bdab..19eb409 100644 --- a/DCCTimerMEGAAVR.cpp +++ b/DCCTimerMEGAAVR.cpp @@ -80,6 +80,14 @@ extern char *__malloc_heap_start; interruptHandler(); } +void DCCTimer::startRailcomTimer(byte brakePin) { + // TODO: for intended operation see DCCTimerAVR.cpp +} + +void DCCTimer::ackRailcomTimer() { + // TODO: for intended operation see DCCTimerAVR.cpp +} + bool DCCTimer::isPWMPin(byte pin) { (void) pin; return false; // TODO what are the relevant pins? diff --git a/DCCTimerSAMD.cpp b/DCCTimerSAMD.cpp index f878ae5..a0b4da5 100644 --- a/DCCTimerSAMD.cpp +++ b/DCCTimerSAMD.cpp @@ -76,6 +76,14 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { interrupts(); } +void DCCTimer::startRailcomTimer(byte brakePin) { + // TODO: for intended operation see DCCTimerAVR.cpp +} + +void DCCTimer::ackRailcomTimer() { + // TODO: for intended operation see DCCTimerAVR.cpp +} + // Timer IRQ handlers replace the dummy handlers (in cortex_handlers) // copied from rf24 branch void TCC0_Handler() { diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index f24adc2..eb7e1ca 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -201,6 +201,14 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { interrupts(); } +void DCCTimer::startRailcomTimer(byte brakePin) { + // TODO: for intended operation see DCCTimerAVR.cpp +} + +void DCCTimer::ackRailcomTimer() { + // TODO: for intended operation see DCCTimerAVR.cpp +} + bool DCCTimer::isPWMPin(byte pin) { //TODO: STM32 whilst this call to digitalPinHasPWM will reveal which pins can do PWM, // there's no support yet for High Accuracy, so for now return false diff --git a/DCCTimerTEENSY.cpp b/DCCTimerTEENSY.cpp index 0619e21..1230180 100644 --- a/DCCTimerTEENSY.cpp +++ b/DCCTimerTEENSY.cpp @@ -39,6 +39,14 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { myDCCTimer.begin(interruptHandler, DCC_SIGNAL_TIME); } +void DCCTimer::startRailcomTimer(byte brakePin) { + // TODO: for intended operation see DCCTimerAVR.cpp +} + +void DCCTimer::ackRailcomTimer() { + // TODO: for intended operation see DCCTimerAVR.cpp +} + bool DCCTimer::isPWMPin(byte pin) { //Teensy: digitalPinHasPWM, todo (void) pin; diff --git a/DCCWaveform.cpp b/DCCWaveform.cpp index 707f8f4..2d50929 100644 --- a/DCCWaveform.cpp +++ b/DCCWaveform.cpp @@ -117,14 +117,17 @@ DCCWaveform::DCCWaveform( byte preambleBits, bool isMain) { } volatile bool DCCWaveform::railcomActive=false; // switched on by user +volatile bool DCCWaveform::railcomDebug=false; // switched on by user -bool DCCWaveform::setRailcom(bool on) { +bool DCCWaveform::setRailcom(bool on, bool debug) { if (on) { // TODO check possible railcomActive=true; + railcomDebug=debug; } else { railcomActive=false; + railcomDebug=false; } return railcomActive; } @@ -225,9 +228,11 @@ void DCCWaveform::promotePendingPacket() { // nothing to do, just send idles or resets // Fortunately reset and idle packets are the same length - // TEMPORARY DEBUG FOR RAILCOM - // memcpy( transmitPacket, isMainTrack ? idlePacket : resetPacket, sizeof(idlePacket)); - memcpy( transmitPacket, resetPacket, sizeof(idlePacket)); + // Note: If railcomDebug is on, then we send resets to the main + // track instead of idles. This means that all data will be zeros + // and only the porersets will be ones, making it much + // easier to read on a logic analyser. + memcpy( transmitPacket, (isMainTrack && (!railcomDebug)) ? idlePacket : resetPacket, sizeof(idlePacket)); transmitLength = sizeof(idlePacket); transmitRepeats = 0; if (getResets() < 250) sentResetsSincePacket++; // only place to increment (private!) @@ -316,4 +321,10 @@ bool DCCWaveform::isReminderWindowOpen() { void IRAM_ATTR DCCWaveform::loop() { DCCACK::checkAck(progTrack.getResets()); } + +bool DCCWaveform::setRailcom(bool on, bool debug) { + // TODO... ESP32 railcom waveform + return false; +} + #endif diff --git a/DCCWaveform.h b/DCCWaveform.h index 3f6de18..a3e20da 100644 --- a/DCCWaveform.h +++ b/DCCWaveform.h @@ -85,7 +85,7 @@ class DCCWaveform { void schedulePacket(const byte buffer[], byte byteCount, byte repeats); bool isReminderWindowOpen(); void promotePendingPacket(); - static bool setRailcom(bool on); + static bool setRailcom(bool on, bool debug); static bool isRailcom() {return railcomActive;} private: @@ -113,6 +113,7 @@ class DCCWaveform { byte pendingLength; byte pendingRepeats; static volatile bool railcomActive; // switched on by user + static volatile bool railcomDebug; // switched on by user #ifdef ARDUINO_ARCH_ESP32 static RMTChannel *rmtMainChannel; From 25cb878060bd50f829a2788338355984e369ef54 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 7 Feb 2024 21:33:06 +0000 Subject: [PATCH 39/54] remove dross --- TrackManager.cpp | 5 ----- TrackManager.h | 1 - version.h | 2 +- 3 files changed, 1 insertion(+), 7 deletions(-) diff --git a/TrackManager.cpp b/TrackManager.cpp index 328f952..ca309ed 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -157,11 +157,6 @@ void TrackManager::setDCCSignal( bool on) { HAVE_PORTF(PORTF=shadowPORTF); } -// Called by interrupt context -void TrackManager::setCutout( bool on) { - APPLY_BY_MODE(TRACK_MODE_MAIN,setBrake(on,true)); -} - // setPROGSignal(), called from interrupt context // does assume ports are shadowed if they can be void TrackManager::setPROGSignal( bool on) { diff --git a/TrackManager.h b/TrackManager.h index 6310030..c1f314a 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -57,7 +57,6 @@ class TrackManager { ); static void setDCCSignal( bool on); - static void setCutout( bool on); static void setPROGSignal( bool on); static void setDCSignal(int16_t cab, byte speedbyte); static MotorDriver * getProgDriver(); diff --git a/version.h b/version.h index e94303f..24bddc6 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,7 @@ #include "StringFormatter.h" -#define VERSION "5.2.28" +#define VERSION "5.2.28-Railcom" // 5.2.28 - ESP32: Can all Wifi channels. // - ESP32: Only write Wifi password to display if it is a well known one // 5.2.27 - Bugfix: IOExpander memory allocation From 8293749ac76199d9b0db6988872c49039f1a4ca8 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 7 Feb 2024 22:11:27 +0000 Subject: [PATCH 40/54] JMRI_SENSOR exrail --- EXRAIL2MacroReset.h | 2 ++ EXRAILMacros.h | 3 +++ Sensors.cpp | 7 +++++++ Sensors.h | 1 + version.h | 3 ++- 5 files changed, 15 insertions(+), 1 deletion(-) diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 3554f6c..f52b636 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -84,6 +84,7 @@ #undef IFTTPOSITION #undef IFRE #undef INVERT_DIRECTION +#undef JMRI_SENSOR #undef JOIN #undef KILLALL #undef LATCH @@ -236,6 +237,7 @@ #define IFTTPOSITION(turntable_id,position) #define IFRE(sensor_id,value) #define INVERT_DIRECTION +#define JMRI_SENSOR(vpin,count...) #define JOIN #define KILLALL #define LATCH(sensor_id) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 98af846..5873e38 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -149,6 +149,8 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU #define HAL(haltype,params...) haltype::create(params); #undef HAL_IGNORE_DEFAULTS #define HAL_IGNORE_DEFAULTS ignore_defaults=true; +#undef JMRI_SENSOR +#define JMRI_SENSOR(vpin,count...) Sensor::createMultiple(vpin,##count); bool exrailHalSetup() { bool ignore_defaults=false; #include "myAutomation.h" @@ -487,6 +489,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #endif #define IFRE(sensor_id,value) OPCODE_IFRE,V(sensor_id),OPCODE_PAD,V(value), #define INVERT_DIRECTION OPCODE_INVERT_DIRECTION,0,0, +#define JMRI_SENSOR(vpin,count...) #define JOIN OPCODE_JOIN,0,0, #define KILLALL OPCODE_KILLALL,0,0, #define LATCH(sensor_id) OPCODE_LATCH,V(sensor_id), diff --git a/Sensors.cpp b/Sensors.cpp index d1c0fe5..efd969d 100644 --- a/Sensors.cpp +++ b/Sensors.cpp @@ -230,6 +230,13 @@ Sensor *Sensor::create(int snum, VPIN pin, int pullUp){ return tt; } +// Creet multiple eponymous sensors based on vpin alone. +void Sensor::createMultiple(VPIN firstPin, byte count) { + for (byte i=0;i types. // 5.2.40 - Bugfix: WiThrottle sendIntro after initial N message as well // 5.2.29 - Added IO_I2CDFPlayer.h to support DFPLayer over I2C connected to NXP SC16IS750/SC16IS752 (currently only single UART for SC16IS752) // - Added enhanced IO_I2CDFPLayer enum commands to EXRAIL2.h From eacf48380b25a0c704bd05f6d2bf9b56ecd93c9e Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 9 Feb 2024 10:15:23 +0000 Subject: [PATCH 41/54] typos in version comments --- version.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/version.h b/version.h index 0252f8a..3b02cf1 100644 --- a/version.h +++ b/version.h @@ -4,8 +4,8 @@ #include "StringFormatter.h" #define VERSION "5.2.31" -// 5.2.31 - Exrail JMRI_SENSORS(vpin [,count]) creates types. -// 5.2.40 - Bugfix: WiThrottle sendIntro after initial N message as well +// 5.2.31 - Exrail JMRI_SENSOR(vpin [,count]) creates types. +// 5.2.30 - Bugfix: WiThrottle sendIntro after initial N message as well // 5.2.29 - Added IO_I2CDFPlayer.h to support DFPLayer over I2C connected to NXP SC16IS750/SC16IS752 (currently only single UART for SC16IS752) // - Added enhanced IO_I2CDFPLayer enum commands to EXRAIL2.h // - Added PLAYSOUND alias of ANOUT to EXRAILMacros.h From 4b97d63cf3ae4320b73696eae0d11f4a41dc3454 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 9 Feb 2024 10:37:51 +0000 Subject: [PATCH 42/54] Remove compiler warnings --- DCCTimerAVR.cpp | 1 + DCCTimerMEGAAVR.cpp | 1 + DCCTimerSAMD.cpp | 1 + DCCTimerSTM32.cpp | 1 + DCCTimerTEENSY.cpp | 1 + 5 files changed, 5 insertions(+) diff --git a/DCCTimerAVR.cpp b/DCCTimerAVR.cpp index 66b51ba..5310704 100644 --- a/DCCTimerAVR.cpp +++ b/DCCTimerAVR.cpp @@ -75,6 +75,7 @@ void DCCTimer::startRailcomTimer(byte brakePin) { (there will be 7 DCC timer1 ticks in which to do this.) */ + (void) brakePin; // Ignored... works on pin 9 only const int cutoutDuration = 430; // Desired interval in microseconds // Set up Timer2 for CTC mode (Clear Timer on Compare Match) diff --git a/DCCTimerMEGAAVR.cpp b/DCCTimerMEGAAVR.cpp index 19eb409..be9337b 100644 --- a/DCCTimerMEGAAVR.cpp +++ b/DCCTimerMEGAAVR.cpp @@ -82,6 +82,7 @@ extern char *__malloc_heap_start; void DCCTimer::startRailcomTimer(byte brakePin) { // TODO: for intended operation see DCCTimerAVR.cpp + (void) brakePin; } void DCCTimer::ackRailcomTimer() { diff --git a/DCCTimerSAMD.cpp b/DCCTimerSAMD.cpp index a0b4da5..d281371 100644 --- a/DCCTimerSAMD.cpp +++ b/DCCTimerSAMD.cpp @@ -78,6 +78,7 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { void DCCTimer::startRailcomTimer(byte brakePin) { // TODO: for intended operation see DCCTimerAVR.cpp + (void) brakePin; } void DCCTimer::ackRailcomTimer() { diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index eb7e1ca..e22758f 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -203,6 +203,7 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { void DCCTimer::startRailcomTimer(byte brakePin) { // TODO: for intended operation see DCCTimerAVR.cpp + (void) brakePin; } void DCCTimer::ackRailcomTimer() { diff --git a/DCCTimerTEENSY.cpp b/DCCTimerTEENSY.cpp index 1230180..d7bb29b 100644 --- a/DCCTimerTEENSY.cpp +++ b/DCCTimerTEENSY.cpp @@ -41,6 +41,7 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { void DCCTimer::startRailcomTimer(byte brakePin) { // TODO: for intended operation see DCCTimerAVR.cpp + (void) brakePin; } void DCCTimer::ackRailcomTimer() { From c780b968564eae454d2001d51b0988f2245b0e02 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 9 Feb 2024 11:54:53 +0000 Subject: [PATCH 43/54] Exrail CONFIGURE_SERVO --- EXRAIL2MacroReset.h | 4 +++- EXRAILMacros.h | 3 +++ version.h | 3 ++- 3 files changed, 8 insertions(+), 2 deletions(-) diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index f52b636..309c325 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -42,6 +42,7 @@ #undef CLEAR_STASH #undef CLEAR_ALL_STASH #undef CLOSE +#undef CONFIGURE_SERVO #undef DCC_SIGNAL #undef DCC_TURNTABLE #undef DEACTIVATE @@ -194,7 +195,8 @@ #define CALL(route) #define CLEAR_STASH(id) #define CLEAR_ALL_STASH(id) -#define CLOSE(id) +#define CLOSE(id) +#define CONFIGURE_SERVO(vpin,pos1,pos2,profile) #define DCC_SIGNAL(id,add,subaddr) #define DCC_TURNTABLE(id,home,description) #define DEACTIVATE(addr,subaddr) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 5873e38..3b579a3 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -151,6 +151,8 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU #define HAL_IGNORE_DEFAULTS ignore_defaults=true; #undef JMRI_SENSOR #define JMRI_SENSOR(vpin,count...) Sensor::createMultiple(vpin,##count); +#undef CONFIGURE_SERVO +#define CONFIGURE_SERVO(vpin,pos1,pos2,profile) IODevice::configureServo(vpin,pos1,pos2,PCA9685::profile); bool exrailHalSetup() { bool ignore_defaults=false; #include "myAutomation.h" @@ -441,6 +443,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define CLEAR_STASH(id) OPCODE_CLEAR_STASH,V(id), #define CLEAR_ALL_STASH OPCODE_CLEAR_ALL_STASH,V(0), #define CLOSE(id) OPCODE_CLOSE,V(id), +#define CONFIGURE_SERVO(vpin,pos1,pos2,profile) #ifndef IO_NO_HAL #define DCC_TURNTABLE(id,home,description...) OPCODE_DCCTURNTABLE,V(id),OPCODE_PAD,V(home), #endif diff --git a/version.h b/version.h index c24efed..84eeedf 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.32" +#define VERSION "5.2.33" +// 5.2.33 - Exrail CONFIGURE_SERVO(vpin,pos1,pos2,profile) // 5.2.32 - Railcom Cutout (Initial trial Mega2560 only) // 5.2.31 - Exrail JMRI_SENSOR(vpin [,count]) creates types. // 5.2.30 - Bugfix: WiThrottle sendIntro after initial N message as well From 784088b0df9363a7f0c9a956f8f19c0963d0030b Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 11 Feb 2024 23:19:51 +0100 Subject: [PATCH 44/54] get it into nano and uno again --- DCCEXParser.cpp | 2 ++ platformio.ini | 6 ++---- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 5b335d2..6deb34f 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1035,6 +1035,7 @@ bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) { DCC::setGlobalSpeedsteps(128); DIAG(F("128 Speedsteps")); return true; +#if defined(HAS_ENOUGH_MEMORY) && !defined(ARDUINO_ARCH_UNO) case "RAILCOM"_hk: { // if (params<2) return false; @@ -1059,6 +1060,7 @@ bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) { ,DCCWaveform::setRailcom(on,debug)?F("ON"):F("OFF")); return true; } +#endif #ifndef DISABLE_PROG case "ACK"_hk: // if (params >= 3) { diff --git a/platformio.ini b/platformio.ini index 2630e6d..a03ff61 100644 --- a/platformio.ini +++ b/platformio.ini @@ -148,10 +148,7 @@ build_flags = platform = atmelavr board = uno framework = arduino -lib_deps = - ${env.lib_deps} - arduino-libraries/Ethernet - SPI +lib_deps = ${env.lib_deps} monitor_speed = 115200 monitor_echo = yes build_flags = -mcall-prologues @@ -164,6 +161,7 @@ framework = arduino lib_deps = ${env.lib_deps} monitor_speed = 115200 monitor_echo = yes +build_flags = -mcall-prologues [env:ESP32] platform = espressif32 From 59b0e8383d0509f784e9ba1108cd11142fa04b68 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Thu, 15 Feb 2024 19:51:52 +0000 Subject: [PATCH 45/54] --- DCC.cpp | 16 ++++++++++++++++ DCC.h | 1 + DCCEXParser.cpp | 9 +++++++++ 3 files changed, 26 insertions(+) diff --git a/DCC.cpp b/DCC.cpp index 0c5148a..ed2a803 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -278,6 +278,22 @@ void DCC::setAccessory(int address, byte port, bool gate, byte onoff /*= 2*/) { } } +void DCC::setExtendedAccessory(int16_t address, int16_t value, byte repeats) { + + // format is 10AAAAAA, 0AAA0AA1, 000XXXXX + if (address != (address & 0x7F)) return; + if (value != (value & 0x1F)) return; + + byte b[3]; + b[0]= 0x80 | ((address & 0x7FF)>>5); + b[1]= 0x01 | ((address & 0x1c)<<2) | (address & 0x03)<<1; + b[2]=value & 0x1F; + DCCWaveform::mainTrack.schedulePacket(b, sizeof(b), repeats); // Repeat on packet three times +#if defined(EXRAIL_ACTIVE) + // TODO RMFT2::activateExtendedEvent(address,value); +#endif +} + // // writeCVByteMain: Write a byte with PoM on main. This writes // the 5 byte sized packet to implement this DCC function diff --git a/DCC.h b/DCC.h index 3bf0cf5..e1aeae6 100644 --- a/DCC.h +++ b/DCC.h @@ -71,6 +71,7 @@ public: static uint32_t getFunctionMap(int cab); static void updateGroupflags(byte &flags, int16_t functionNumber); static void setAccessory(int address, byte port, bool gate, byte onoff = 2); + static void setExtendedAccessory(int16_t address, int16_t value, byte repeats=3); static bool writeTextPacket(byte *b, int nBytes); // ACKable progtrack calls bitresults callback 0,0 or -1, cv returns value or -1 diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 6deb34f..a3aa1c4 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -384,6 +384,15 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) #endif } return; + + case 'A': // EXTENDED ACCESSORY + { + if (params!=2) break; + if (p[0] != (p[0] & 0x7F)) break; + if (p[1] != (p[1] & 0x1F)) break; + DCC::setExtendedAccessory(p[0],p[1],3); + } + return; case 'T': // TURNOUT if (parseT(stream, params, p)) From e4904e40802ca3f1a8e9a6b82d2f06cddd4f81e2 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Thu, 15 Feb 2024 20:05:27 +0000 Subject: [PATCH 46/54] Exrail ASPECT(addr,value) --- EXRAIL2.cpp | 5 +++++ EXRAIL2.h | 2 +- EXRAIL2MacroReset.h | 2 ++ EXRAILMacros.h | 4 ++++ 4 files changed, 12 insertions(+), 1 deletion(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 8a2eadf..56aeeb2 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -800,6 +800,11 @@ void RMFT2::loop2() { DCC::setAccessory(addr,subaddr,active); break; } + case OPCODE_ASPECT: { + // operand is address<<5 | value + DCC::setExtendedAccessory(operand>>5, operand & 0x1F); + break; + } case OPCODE_FOLLOW: progCounter=routeLookup->find(operand); diff --git a/EXRAIL2.h b/EXRAIL2.h index ccfbbe6..e8235c6 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -54,7 +54,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_START,OPCODE_SETLOCO,OPCODE_SENDLOCO,OPCODE_FORGET, OPCODE_PAUSE, OPCODE_RESUME,OPCODE_POWEROFF,OPCODE_POWERON, OPCODE_ONCLOSE, OPCODE_ONTHROW, OPCODE_SERVOTURNOUT, OPCODE_PINTURNOUT, - OPCODE_PRINT,OPCODE_DCCACTIVATE, + OPCODE_PRINT,OPCODE_DCCACTIVATE,OPCODE_ASPECT, OPCODE_ONACTIVATE,OPCODE_ONDEACTIVATE, OPCODE_ROSTER,OPCODE_KILLALL, OPCODE_ROUTE,OPCODE_AUTOMATION,OPCODE_SEQUENCE, diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 309c325..633f4d5 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -31,6 +31,7 @@ #undef ALIAS #undef AMBER #undef ANOUT +#undef ASPECT #undef AT #undef ATGTE #undef ATLT @@ -186,6 +187,7 @@ #define AMBER(signal_id) #define ANOUT(vpin,value,param1,param2) #define AT(sensor_id) +#define ASPECT(address,value) #define ATGTE(sensor_id,value) #define ATLT(sensor_id,value) #define ATTIMEOUT(sensor_id,timeout_ms) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 3b579a3..8d870ef 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -117,6 +117,9 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU // - check range on LATCH/UNLATCH // This pass generates no runtime data or code #include "EXRAIL2MacroReset.h" +#undef ASPECT +#define ASPECT(address,value) static_assert((address & 0x7ff)== address, "invalid Address"); \ + static_assert((value & 0x1F)== value, "Invalid value"); #undef CALL #define CALL(id) static_assert(hasseq(id),"Sequence not found"); #undef FOLLOW @@ -432,6 +435,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define ALIAS(name,value...) #define AMBER(signal_id) OPCODE_AMBER,V(signal_id), #define ANOUT(vpin,value,param1,param2) OPCODE_SERVO,V(vpin),OPCODE_PAD,V(value),OPCODE_PAD,V(param1),OPCODE_PAD,V(param2), +#define ASPECT(address,value) OPCODE_ASPECT,V((address<<5) | (value & 0x1F)), #define AT(sensor_id) OPCODE_AT,V(sensor_id), #define ATGTE(sensor_id,value) OPCODE_ATGTE,V(sensor_id),OPCODE_PAD,V(value), #define ATLT(sensor_id,value) OPCODE_ATLT,V(sensor_id),OPCODE_PAD,V(value), From 8705c8c33f0255b46a2925cbe9453d87a90c2c79 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 16 Feb 2024 11:49:02 +0000 Subject: [PATCH 47/54] DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect) --- EXRAIL2.cpp | 12 +++++++++++- EXRAIL2.h | 1 + EXRAIL2MacroReset.h | 2 ++ EXRAILMacros.h | 5 +++++ 4 files changed, 19 insertions(+), 1 deletion(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 56aeeb2..6f0420c 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -1066,7 +1066,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) { if (diag) DIAG(F(" doSignal %d %x"),id,rag); // Schedule any event handler for this signal change. - // Thjis will work even without a signal definition. + // This will work even without a signal definition. if (rag==SIGNAL_RED) onRedLookup->handleEvent(F("RED"),id); else if (rag==SIGNAL_GREEN) onGreenLookup->handleEvent(F("GREEN"),id); else onAmberLookup->handleEvent(F("AMBER"),id); @@ -1103,6 +1103,16 @@ int16_t RMFT2::getSignalSlot(int16_t id) { return; } + if (sigtype== DCCX_SIGNAL_FLAG) { + // redpin,amberpin,greenpin are the 3 aspects + byte value=redpin; + if (rag==SIGNAL_AMBER) value=amberpin; + if (rag==SIGNAL_GREEN) value=greenpin; + DCC::setExtendedAccessory(sigid & SIGNAL_ID_MASK,value); + return; + } + + // LED or similar 3 pin signal, (all pins zero would be a virtual signal) // If amberpin is zero, synthesise amber from red+green const byte SIMAMBER=0x00; diff --git a/EXRAIL2.h b/EXRAIL2.h index e8235c6..eec2a06 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -158,6 +158,7 @@ class LookList { static const int16_t SERVO_SIGNAL_FLAG=0x4000; static const int16_t ACTIVE_HIGH_SIGNAL_FLAG=0x2000; static const int16_t DCC_SIGNAL_FLAG=0x1000; + static const int16_t DCCX_SIGNAL_FLAG=0x3000; static const int16_t SIGNAL_ID_MASK=0x0FFF; // Throttle Info Access functions built by exrail macros static const byte rosterNameCount; diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 633f4d5..723bef2 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -45,6 +45,7 @@ #undef CLOSE #undef CONFIGURE_SERVO #undef DCC_SIGNAL +#undef DCCX_SIGNAL #undef DCC_TURNTABLE #undef DEACTIVATE #undef DEACTIVATEL @@ -200,6 +201,7 @@ #define CLOSE(id) #define CONFIGURE_SERVO(vpin,pos1,pos2,profile) #define DCC_SIGNAL(id,add,subaddr) +#define DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect) #define DCC_TURNTABLE(id,home,description) #define DEACTIVATE(addr,subaddr) #define DEACTIVATEL(addr) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 8d870ef..698451e 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -172,6 +172,8 @@ bool exrailHalSetup() { #define SERVO_SIGNAL(vpin,redval,amberval,greenval) | FEATURE_SIGNAL #undef DCC_SIGNAL #define DCC_SIGNAL(id,addr,subaddr) | FEATURE_SIGNAL +#undef DCCX_SIGNAL +#define DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect) | FEATURE_SIGNAL #undef VIRTUAL_SIGNAL #define VIRTUAL_SIGNAL(id) | FEATURE_SIGNAL @@ -401,6 +403,8 @@ const FSH * RMFT2::getRosterFunctions(int16_t id) { #define SERVO_SIGNAL(vpin,redval,amberval,greenval) vpin | RMFT2::SERVO_SIGNAL_FLAG,redval,amberval,greenval, #undef DCC_SIGNAL #define DCC_SIGNAL(id,addr,subaddr) id | RMFT2::DCC_SIGNAL_FLAG,addr,subaddr,0, +#undef DCCX_SIGNAL +#define DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect) id | RMFT2::DCCX_SIGNAL_FLAG,redAspect,amberAspect,greenAspect, #undef VIRTUAL_SIGNAL #define VIRTUAL_SIGNAL(id) id,0,0,0, @@ -457,6 +461,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define DELAYMINS(mindelay) OPCODE_DELAYMINS,V(mindelay), #define DELAYRANDOM(mindelay,maxdelay) DELAY(mindelay) OPCODE_RANDWAIT,V((maxdelay-mindelay)/100L), #define DCC_SIGNAL(id,add,subaddr) +#define DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect) #define DONE OPCODE_ENDTASK,0,0, #define DRIVE(analogpin) OPCODE_DRIVE,V(analogpin), #define ELSE OPCODE_ELSE,0,0, From 5742b71ec608e79feaedba1b14322187d960474c Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 16 Feb 2024 12:20:58 +0000 Subject: [PATCH 48/54] to EXRAIL DCCX_SIGNAL intercept --- DCCEXParser.cpp | 6 ++++++ EXRAIL2.cpp | 32 ++++++++++++++++++++++++++++++++ EXRAIL2.h | 3 ++- 3 files changed, 40 insertions(+), 1 deletion(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index a3aa1c4..bcd258a 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -390,6 +390,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) if (params!=2) break; if (p[0] != (p[0] & 0x7F)) break; if (p[1] != (p[1] & 0x1F)) break; +#ifdef EXRAIL_ACTIVE + // Ask exrail if this is just changing the aspect on a + // predefined DCCX_SIGNAL. Because this will handle all + // the IFRED and ONRED type issues at the same time. + if (RMFT2::signalAspectEvent(p[0],p[1])) return; +#endif DCC::setExtendedAccessory(p[0],p[1],3); } return; diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 6f0420c..928bc79 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -1146,6 +1146,38 @@ int16_t RMFT2::getSignalSlot(int16_t id) { return (flags[sigslot] & SIGNAL_MASK) == rag; } + +// signalAspectEvent returns true if the aspect is destined +// for a defined DCCX_SIGNAL which will handle all the RAG flags +// and ON* handlers. +// Otherwise false so the parser should send the command directly +bool RMFT2::signalAspectEvent(int16_t address, byte aspect ) { + if (!(compileFeatures & FEATURE_SIGNAL)) return false; + int16_t sigslot=getSignalSlot(address); + if (sigslot<0) return false; // this is not a defined signal + int16_t sigpos=sigslot*8; + VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos); + VPIN sigtype=sigid & ~SIGNAL_ID_MASK; + if (sigtype!=DCCX_SIGNAL_FLAG) return false; // not a DCCX signal + // Turn an aspect change into a RED/AMBER/GREEN setting + if (aspect==GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+2)) { + doSignal(sigid,SIGNAL_RED); + return true; + } + + if (aspect==GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+4)) { + doSignal(sigid,SIGNAL_AMBER); + return true; + } + + if (aspect==GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+6)) { + doSignal(sigid,SIGNAL_GREEN); + return true; + } + + return false; // aspect is not a defined one +} + void RMFT2::turnoutEvent(int16_t turnoutId, bool closed) { // Hunt for an ONTHROW/ONCLOSE for this turnout if (closed) onCloseLookup->handleEvent(F("CLOSE"),turnoutId); diff --git a/EXRAIL2.h b/EXRAIL2.h index eec2a06..914c822 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -155,6 +155,7 @@ class LookList { static void clockEvent(int16_t clocktime, bool change); static void rotateEvent(int16_t id, bool change); static void powerEvent(int16_t track, bool overload); + static bool signalAspectEvent(int16_t address, byte aspect ); static const int16_t SERVO_SIGNAL_FLAG=0x4000; static const int16_t ACTIVE_HIGH_SIGNAL_FLAG=0x2000; static const int16_t DCC_SIGNAL_FLAG=0x1000; @@ -173,7 +174,7 @@ class LookList { static const FSH * getTurntableDescription(int16_t id); static const FSH * getTurntablePositionDescription(int16_t turntableId, uint8_t positionId); static void startNonRecursiveTask(const FSH* reason, int16_t id,int pc); - + private: static void ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]); static bool parseSlash(Print * stream, byte & paramCount, int16_t p[]) ; From 7ee4188d88e899007658a197db6bea25ae47b492 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 16 Feb 2024 12:36:33 +0000 Subject: [PATCH 49/54] Tidy and version --- DCCEXParser.cpp | 11 ++++------- EXRAIL2.cpp | 5 ++++- EXRAIL2Parser.cpp | 8 ++++++++ version.h | 6 +++++- 4 files changed, 21 insertions(+), 9 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index bcd258a..d66b51f 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -387,16 +387,13 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) case 'A': // EXTENDED ACCESSORY { + // Note: if this happens to match a defined EXRAIL + // DCCX_SIGNAL, then EXRAIL will have intercepted + // this command alrerady. if (params!=2) break; if (p[0] != (p[0] & 0x7F)) break; if (p[1] != (p[1] & 0x1F)) break; -#ifdef EXRAIL_ACTIVE - // Ask exrail if this is just changing the aspect on a - // predefined DCCX_SIGNAL. Because this will handle all - // the IFRED and ONRED type issues at the same time. - if (RMFT2::signalAspectEvent(p[0],p[1])) return; -#endif - DCC::setExtendedAccessory(p[0],p[1],3); + DCC::setExtendedAccessory(p[0],p[1]); } return; diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 928bc79..014e42b 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -802,7 +802,10 @@ void RMFT2::loop2() { } case OPCODE_ASPECT: { // operand is address<<5 | value - DCC::setExtendedAccessory(operand>>5, operand & 0x1F); + int16_t address=operand>>5; + byte aspect=operand & 0x1f; + if (!signalAspectEvent(address,aspect)) + DCC::setExtendedAccessory(address,aspect); break; } diff --git a/EXRAIL2Parser.cpp b/EXRAIL2Parser.cpp index 99f0c37..7969750 100644 --- a/EXRAIL2Parser.cpp +++ b/EXRAIL2Parser.cpp @@ -51,6 +51,14 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 opcode=0; break; + case 'A': // + if (paramCount!=2) break; + // Ask exrail if this is just changing the aspect on a + // predefined DCCX_SIGNAL. Because this will handle all + // the IFRED and ONRED type issues at the same time. + if (signalAspectEvent(p[0],p[1])) opcode=0; // all done + break; + case 'L': // This entire code block is compiled out if LLC macros not used if (!(compileFeatures & FEATURE_LCC)) return; diff --git a/version.h b/version.h index 84eeedf..341c61e 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,11 @@ #include "StringFormatter.h" -#define VERSION "5.2.33" +#define VERSION "5.2.34" +// 5.2.34 - Command fopr DCC Extended Accessories +// - Exrail ASPECT(address,aspect) for above. +// - EXRAIL DCCX_SIGNAL(Address,redAspect,amberAspect,greenAspect) +// - Exrail intercept for DCC Signals. // 5.2.33 - Exrail CONFIGURE_SERVO(vpin,pos1,pos2,profile) // 5.2.32 - Railcom Cutout (Initial trial Mega2560 only) // 5.2.31 - Exrail JMRI_SENSOR(vpin [,count]) creates types. From 7e4093f03fd96b76fb6cdbceb2c0b91918a86b8a Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 16 Feb 2024 12:45:33 +0000 Subject: [PATCH 50/54] comment only --- DCCEXParser.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index d66b51f..af6c4ee 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -45,7 +45,7 @@ Once a new OPCODE is decided upon, update this list. 0, Track power off 1, Track power on a, DCC accessory control - A, + A, DCC extended accessory control b, Write CV bit on main B, Write CV bit c, Request current command From dcd332603c1cc97f0474f7e1266b76d1fa7af3ae Mon Sep 17 00:00:00 2001 From: Asbelos Date: Sat, 17 Feb 2024 11:09:03 +0000 Subject: [PATCH 51/54] accessory packet issues. --- DCC.cpp | 40 +++++++++++++++++++++++++++++----------- DCC.h | 2 +- DCCEXParser.cpp | 17 ++++++----------- 3 files changed, 36 insertions(+), 23 deletions(-) diff --git a/DCC.cpp b/DCC.cpp index ed2a803..8a6e8e0 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -278,21 +278,39 @@ void DCC::setAccessory(int address, byte port, bool gate, byte onoff /*= 2*/) { } } -void DCC::setExtendedAccessory(int16_t address, int16_t value, byte repeats) { +bool DCC::setExtendedAccessory(int16_t address, int16_t value, byte repeats) { + +/* From https://www.nmra.org/sites/default/files/s-9.2.1_2012_07.pdf + +The Extended Accessory Decoder Control Packet is included for the purpose of transmitting aspect control to signal +decoders or data bytes to more complex accessory decoders. Each signal head can display one aspect at a time. +{preamble} 0 10AAAAAA 0 0AAA0AA1 0 000XXXXX 0 EEEEEEEE 1 + +XXXXX is for a single head. A value of 00000 for XXXXX indicates the absolute stop aspect. All other aspects +represented by the values for XXXXX are determined by the signaling system used and the prototype being +modeled. +*/ +/* CAH Notes: +Thus in byte packet form the format is 10AAAAAA, 0AAA0AA1, 000XXXXX + +Note that the Basic accessory format mentions +"By convention these bits (bits 4-6 of the second data byte) are in ones complement" +but this note is absent from the advanced packet description. +The (~address) construct below applies this because this appears to be +required. + +*/ + if (address != (address & 0x7FF)) return false; // 11 bits + if (value != (value & 0x1F)) return false; // 5 bits - // format is 10AAAAAA, 0AAA0AA1, 000XXXXX - if (address != (address & 0x7F)) return; - if (value != (value & 0x1F)) return; byte b[3]; - b[0]= 0x80 | ((address & 0x7FF)>>5); - b[1]= 0x01 | ((address & 0x1c)<<2) | (address & 0x03)<<1; - b[2]=value & 0x1F; + b[0]= 0x80 | (address>>5); + b[1]= 0x01 | (((~address) & 0x1c)<<2) | ((address & 0x03)<<1); + b[2]=value; DCCWaveform::mainTrack.schedulePacket(b, sizeof(b), repeats); // Repeat on packet three times -#if defined(EXRAIL_ACTIVE) - // TODO RMFT2::activateExtendedEvent(address,value); -#endif -} + return true; + } // // writeCVByteMain: Write a byte with PoM on main. This writes diff --git a/DCC.h b/DCC.h index e1aeae6..aa93520 100644 --- a/DCC.h +++ b/DCC.h @@ -71,7 +71,7 @@ public: static uint32_t getFunctionMap(int cab); static void updateGroupflags(byte &flags, int16_t functionNumber); static void setAccessory(int address, byte port, bool gate, byte onoff = 2); - static void setExtendedAccessory(int16_t address, int16_t value, byte repeats=3); + static bool setExtendedAccessory(int16_t address, int16_t value, byte repeats=3); static bool writeTextPacket(byte *b, int nBytes); // ACKable progtrack calls bitresults callback 0,0 or -1, cv returns value or -1 diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index af6c4ee..db78d71 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -385,17 +385,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } return; - case 'A': // EXTENDED ACCESSORY - { - // Note: if this happens to match a defined EXRAIL - // DCCX_SIGNAL, then EXRAIL will have intercepted - // this command alrerady. - if (params!=2) break; - if (p[0] != (p[0] & 0x7F)) break; - if (p[1] != (p[1] & 0x1F)) break; - DCC::setExtendedAccessory(p[0],p[1]); - } - return; + case 'A': // EXTENDED ACCESSORY + // Note: if this happens to match a defined EXRAIL + // DCCX_SIGNAL, then EXRAIL will have intercepted + // this command alrerady. + if (params==2 && DCC::setExtendedAccessory(p[0],p[1])) return; + break; case 'T': // TURNOUT if (parseT(stream, params, p)) From fbbedc7577ab390e22235ffab111384179ed53be Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 17 Feb 2024 18:51:13 +0100 Subject: [PATCH 52/54] make ext acc packet format follow RCN-213 --- DCC.cpp | 45 +++++++++++++++++++++++++++++++-------------- 1 file changed, 31 insertions(+), 14 deletions(-) diff --git a/DCC.cpp b/DCC.cpp index 8a6e8e0..a435eeb 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -289,28 +289,45 @@ decoders or data bytes to more complex accessory decoders. Each signal head can XXXXX is for a single head. A value of 00000 for XXXXX indicates the absolute stop aspect. All other aspects represented by the values for XXXXX are determined by the signaling system used and the prototype being modeled. -*/ -/* CAH Notes: + +From https://normen.railcommunity.de/RCN-213.pdf: + +More information is in RCN-213 about how the address bits are organized. +preamble -0- 1 0 A7 A6 A5 A4 A3 A2 -0- 0 ^A10 ^A9 ^A8 0 A1 A0 1 -0- .... + Thus in byte packet form the format is 10AAAAAA, 0AAA0AA1, 000XXXXX -Note that the Basic accessory format mentions -"By convention these bits (bits 4-6 of the second data byte) are in ones complement" -but this note is absent from the advanced packet description. -The (~address) construct below applies this because this appears to be -required. +Die Adresse für den ersten erweiterten Zubehördecoder ist wie bei den einfachen +Zubehördecodern die Adresse 4 = 1000-0001 0111-0001 . Diese Adresse wird in +Anwenderdialogen als Adresse 1 dargestellt. +This means that the first address shown to the user as "1" is mapped +to internal address 4. + +Note that the Basic accessory format mentions "By convention these +bits (bits 4-6 of the second data byte) are in ones complement" but +this note is absent from the advanced packet description. The +english translation does not mention that the address format for +the advanced packet follows the one for the basic packet but +according to the RCN-213 this is the case. + +We allow for addresses from -3 to 2047-3 as that allows to address the +whole range of the 11 bits sent to track. */ - if (address != (address & 0x7FF)) return false; // 11 bits - if (value != (value & 0x1F)) return false; // 5 bits + if ((address > 2044) || (address < -3)) return false; // 2047-3, 11 bits but offset 3 + if (value != (value & 0x1F)) return false; // 5 bits - + address+=3; // +3 offset according to RCN-213 byte b[3]; - b[0]= 0x80 | (address>>5); - b[1]= 0x01 | (((~address) & 0x1c)<<2) | ((address & 0x03)<<1); + b[0]= 0x80 // bits always on + | ((address>>2) & 0x3F); // shift out 2, mask out used bits + b[1]= 0x01 // bits always on + | (((~(address>>8)) & 0x07)<<4) // shift out 8, invert, mask 3 bits, shift up 4 + | ((address & 0x03)<<1); // mask 2 bits, shift up 1 b[2]=value; - DCCWaveform::mainTrack.schedulePacket(b, sizeof(b), repeats); // Repeat on packet three times + DCCWaveform::mainTrack.schedulePacket(b, sizeof(b), repeats); return true; - } +} // // writeCVByteMain: Write a byte with PoM on main. This writes From fe9b1da8a3bcdced2465074dd882689d93e29b31 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 17 Feb 2024 18:52:48 +0100 Subject: [PATCH 53/54] version 5.2.35 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 956a8d2..40e7ece 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202402050827Z" +#define GITHUB_SHA "devel-202402171752Z" diff --git a/version.h b/version.h index 341c61e..d1d6416 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.34" +#define VERSION "5.2.35" +// 5.2.35 - Bugfix: Make DCC Extended Accessories follow RCN-213 // 5.2.34 - Command fopr DCC Extended Accessories // - Exrail ASPECT(address,aspect) for above. // - EXRAIL DCCX_SIGNAL(Address,redAspect,amberAspect,greenAspect) From 821115caaddd513152d277a5e5e4426bad8f9b58 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Mon, 19 Feb 2024 20:02:01 +0000 Subject: [PATCH 54/54] Make ASSERT macro match 5.2.35 --- EXRAILMacros.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 698451e..f0cb150 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -118,8 +118,8 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU // This pass generates no runtime data or code #include "EXRAIL2MacroReset.h" #undef ASPECT -#define ASPECT(address,value) static_assert((address & 0x7ff)== address, "invalid Address"); \ - static_assert((value & 0x1F)== value, "Invalid value"); +#define ASPECT(address,value) static_assert(address <=2044, "invalid Address"); \ + static_assert(address>=-3, "Invalid value"); #undef CALL #define CALL(id) static_assert(hasseq(id),"Sequence not found"); #undef FOLLOW