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

Compare commits

...

30 Commits

Author SHA1 Message Date
Harald Barth
8d9067c86b tag 2024-02-07 15:54:13 +01:00
Harald Barth
e7ed9ffbde compiles on esp32-s3 2024-02-07 15:53:45 +01:00
Harald Barth
4931c5ed75 tag 2024-02-05 09:28:07 +01:00
kempe63
53fec9bc3a Merge branch 'devel' of https://github.com/DCC-EX/CommandStation-EX into devel 2024-02-04 18:57:50 +00:00
kempe63
4780ea63cf Prepend I2CDFPlayer with DF_ to solve Nucleo RESET directive
Prepend all I2CDFPlayer EXRail commands with DF_ to solve a Nucleo defined RESET
2024-02-04 18:57:30 +00:00
Harald Barth
5f6e18e1e7 remove mega328 from default build env list 2024-02-04 13:59:10 +01:00
Harald Barth
be40a7e274 version 5.2.30 2024-02-04 12:51:41 +01:00
Harald Barth
e7f82bdf92 WiThrottle sendIntro after initial N message as well 2024-02-04 12:49:55 +01:00
kempe63
63702ae64e Update fro myHal.cpp_example.txt
Noticed some ommissions, corrected now
2024-02-03 19:27:58 +00:00
kempe63
7cbf4de1b9 Update myHal.cpp_example.txt
Update with instructions for IO_ I2CDFPlayer
2024-02-03 19:25:41 +00:00
kempe63
3c4e4bb14d 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
2024-02-03 19:05:56 +00:00
Harald Barth
6d0740eab4 version 5.2.28 2024-01-21 21:11:57 +01:00
Harald Barth
0a52a26d50 ESP32: Can all Wifi channels. Only write Wifi password to display if it is a well known one 2024-01-21 21:09:55 +01:00
Harald Barth
811bce4b2a tag 2024-01-20 22:16:26 +01:00
Harald Barth
cf1e1c92b3 Check "easy" check first 2024-01-20 22:15:47 +01:00
peteGSX
657c08c653 Update EX-IOExpander copyright 2024-01-18 18:56:15 +10:00
Harald Barth
bc37a2d2cf version 5.2.27 2024-01-18 08:22:28 +01:00
Harald Barth
3c0704dbd1 Bugfix: allocate enough bytes for digital pins. Add more sanity checks when allocating memory 2024-01-18 08:20:33 +01:00
Asbelos
95bf5aae38 HAL defaults control 2024-01-14 20:20:22 +00:00
Asbelos
8216579f62 5.2.25 <D> returns <X> bugs 2024-01-14 02:09:22 +00:00
Asbelos
a54a262f68 5.2.24 EXRAIL asserts 2024-01-14 02:03:42 +00:00
Asbelos
a508ee7055 Fix asserts for Teensy 2024-01-10 16:08:11 +00:00
Harald Barth
20ae915eaf remove unused ccr_reg variable 2024-01-10 15:23:52 +01:00
Harald Barth
35a0bde115 Merge branch 'devel' of https://github.com/DCC-EX/CommandStation-EX into devel 2024-01-10 15:10:57 +01:00
Harald Barth
d24d09c37a subversion 2024-01-10 15:10:25 +01:00
Harald Barth
9ab6b3d4ea Bugfix: Ethernet fixed IP start 2024-01-10 15:09:22 +01:00
Asbelos
d8c282434c _hk in myAutomation 2024-01-10 12:11:14 +00:00
Asbelos
43648fd9f4 5.2.23 2024-01-10 12:01:40 +00:00
Asbelos
b5ddade2b3 Merge branch 'devel' of https://github.com/DCC-EX/CommandStation-EX into devel 2024-01-10 11:58:37 +00:00
Asbelos
2e4995cab3 Keyword Hasher _hk 2024-01-10 11:58:30 +00:00
22 changed files with 1189 additions and 224 deletions

View File

@@ -49,6 +49,7 @@
#include "CommandDistributor.h"
#include "TrackManager.h"
#include "DCCTimer.h"
#include "KeywordHasher.h"
#include "EXRAIL.h"
#endif

View File

@@ -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("<p1 %c>\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; // <J>
int16_t id=(params==2)?p[1]:0;
switch(p[0]) {
case HASH_KEYWORD_C: // <JC mmmm nn> sets time and speed
case "C"_hk: // <JC mmmm nn> sets time and speed
if (params==1) { // <JC> returns latest time
int16_t x = CommandDistributor::retClockTime();
StringFormatter::send(stream, F("<jC %d>\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: // <JG> current gauge limits
case "G"_hk: // <JG> current gauge limits
if (params>1) break;
TrackManager::reportGauges(stream); // <g limit...limit>
return;
case HASH_KEYWORD_I: // <JI> current values
case "I"_hk: // <JI> current values
if (params>1) break;
TrackManager::reportCurrent(stream); // <g limit...limit>
return;
case HASH_KEYWORD_A: // <JA> intercepted by EXRAIL// <JA> returns automations/routes
case "A"_hk: // <JA> intercepted by EXRAIL// <JA> returns automations/routes
if (params!=1) break; // <JA>
StringFormatter::send(stream, F("<jA>\n"));
return;
case HASH_KEYWORD_M: // <JM> intercepted by EXRAIL
case "M"_hk: // <JM> intercepted by EXRAIL
if (params>1) break; // invalid cant do
// <JM> requests stash size so say none.
StringFormatter::send(stream,F("<jM 0>\n"));
return;
case HASH_KEYWORD_R: // <JR> returns rosters
case "R"_hk: // <JR> returns rosters
StringFormatter::send(stream, F("<jR"));
#ifdef EXRAIL_ACTIVE
if (params==1) {
@@ -753,7 +703,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
#endif
StringFormatter::send(stream, F(">\n"));
return;
case HASH_KEYWORD_T: // <JT> returns turnout list
case "T"_hk: // <JT> returns turnout list
StringFormatter::send(stream, F("<jT"));
if (params==1) { // <JT>
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: // <JO returns turntable list
case "O"_hk: // <JO returns turntable list
StringFormatter::send(stream, F("<jO"));
if (params==1) { // <JO>
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: // <JP id> returns turntable position list for the turntable id
case "P"_hk: // <JP id> returns turntable position list for the turntable id
if (params==2) { // <JP id>
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) { // <T id SERVO n n n n>
if (params == 6 && p[1] == "SERVO"_hk) { // <T id SERVO n n n n>
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) { // <T id VPIN n>
if (params == 3 && p[1] == "VPIN"_hk) { // <T id VPIN n>
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) {
// <T id DCC addr subadd> 0<=addr<=511, 0<=subadd<=3 (like <a> command).<T>
if (params==4 && p[2]>=0 && p[2]<512 && p[3]>=0 && p[3]<4) { // <T id DCC n m>
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 <X> 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: // <D ACK ON/OFF> <D ACK [LIMIT|MIN|MAX|RETRY] Value>
case "ACK"_hk: // <D ACK ON/OFF> <D ACK [LIMIT|MIN|MAX|RETRY] Value>
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]); // <D ACK LIMIT 42>
} 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]); // <D ACK MIN 1500>
} 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]); // <D ACK MAX 9000>
} 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])); // <D ACK RETRY 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,66 +1071,66 @@ 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: // <D CABS>
case "CABS"_hk: // <D CABS>
DCC::displayCabList(stream);
return true;
case HASH_KEYWORD_RAM: // <D RAM>
case "RAM"_hk: // <D RAM>
DIAG(F("Free memory=%d"), DCCTimer::getMinimumFreeMemory());
return true;
case HASH_KEYWORD_CMD: // <D CMD ON/OFF>
case "CMD"_hk: // <D CMD ON/OFF>
Diag::CMD = onOff;
return true;
#ifdef HAS_ENOUGH_MEMORY
case HASH_KEYWORD_WIFI: // <D WIFI ON/OFF>
case "WIFI"_hk: // <D WIFI ON/OFF>
Diag::WIFI = onOff;
return true;
case HASH_KEYWORD_ETHERNET: // <D ETHERNET ON/OFF>
case "ETHERNET"_hk: // <D ETHERNET ON/OFF>
Diag::ETHERNET = onOff;
return true;
case HASH_KEYWORD_WIT: // <D WIT ON/OFF>
case "WIT"_hk: // <D WIT ON/OFF>
Diag::WITHROTTLE = onOff;
return true;
case HASH_KEYWORD_LCN: // <D LCN ON/OFF>
case "LCN"_hk: // <D LCN ON/OFF>
Diag::LCN = onOff;
return true;
#endif
#ifndef DISABLE_EEPROM
case HASH_KEYWORD_EEPROM: // <D EEPROM NumEntries>
case "EEPROM"_hk: // <D EEPROM NumEntries>
if (params >= 2)
EEStore::dump(p[1]);
return true;
#endif
case HASH_KEYWORD_SERVO: // <D SERVO vpin position [profile]>
case "SERVO"_hk: // <D SERVO vpin position [profile]>
case HASH_KEYWORD_ANOUT: // <D ANOUT vpin position [profile]>
case "ANOUT"_hk: // <D ANOUT vpin position [profile]>
IODevice::writeAnalogue(p[1], p[2], params>3 ? p[3] : 0);
break;
return true;
case HASH_KEYWORD_ANIN: // <D ANIN vpin> Display analogue input value
case "ANIN"_hk: // <D ANIN vpin> 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 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;
return true;
#endif
case HASH_KEYWORD_TT: // <D TT vpin steps activity>
case "TT"_hk: // <D TT vpin steps activity>
IODevice::writeAnalogue(p[1], p[2], params>3 ? p[3] : 0);
break;
return true;
default: // invalid/unknown
return parseC(stream, params, p);
@@ -1232,7 +1182,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[])
case 3: // <I id position activity> | <I id DCC home> - 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: // <I id EXTT vpin home> 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: // <I id ADD position value angle> 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]);

View File

@@ -83,18 +83,26 @@ int DCCTimer::freeMemory() {
#include <soc/sens_struct.h>
#undef ADC_INPUT_MAX_VALUE
#define ADC_INPUT_MAX_VALUE 4095 // 12 bit ADC
#ifdef ARDUINO_ESP32S3_DEV
#define pinToADC1Channel(X) (adc1_channel_t)((X)-1)
#define MY_SAR_REG sar_meas1_ctrl2
#else
#define pinToADC1Channel(X) (adc1_channel_t)(((X) > 35) ? (X)-36 : (X)-28)
#define MY_SAR_REG sar_meas_start1
#endif
int IRAM_ATTR local_adc1_get_raw(int channel) {
uint16_t adc_value;
SENS.sar_meas_start1.sar1_en_pad = (1 << channel); // only one channel is selected
SENS.MY_SAR_REG.sar1_en_pad = (1 << channel); // only one channel is selected
while (SENS.sar_slave_addr1.meas_status != 0);
SENS.sar_meas_start1.meas1_start_sar = 0;
SENS.sar_meas_start1.meas1_start_sar = 1;
while (SENS.sar_meas_start1.meas1_done_sar == 0);
adc_value = SENS.sar_meas_start1.meas1_data_sar;
SENS.MY_SAR_REG.meas1_start_sar = 0;
SENS.MY_SAR_REG.meas1_start_sar = 1;
while (SENS.MY_SAR_REG.meas1_done_sar == 0);
adc_value = SENS.MY_SAR_REG.meas1_data_sar;
return adc_value;
}
#undef MY_SAR_REG
#include "DCCTimer.h"
INTERRUPT_CALLBACK interruptHandler=0;

View File

@@ -258,4 +258,23 @@ private:
#define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter)
#define SKIPOP progCounter+=3
// IO_I2CDFPlayer commands and values
enum : uint8_t{
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

View File

@@ -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)

View File

@@ -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) { // <D EXRAIL ON/OFF>
diag = paramCount==2 && (p[1]==HASH_KEYWORD_ON || p[1]==1);
if (p[0]=="EXRAIL"_hk) { // <D EXRAIL ON/OFF>
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: // <JA> returns automations/routes
case "A"_hk: // <JA> returns automations/routes
if (paramCount==1) {// <JA>
StringFormatter::send(stream, F("<jA"));
routeLookup->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 <J<> 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: // </ PAUSE>
case "PAUSE"_hk: // </ PAUSE>
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: // </ RESUME>
case "RESUME"_hk: // </ RESUME>
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: // </ START [cab] route >
case "START"_hk: // </ START [cab] route >
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;

View File

@@ -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
@@ -74,13 +78,81 @@
#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<MAX_FLAGS,"Id out of valid range 0-255" );
#undef UNLATCH
#define UNLATCH(id) static_assert(id>=0 && id<MAX_FLAGS,"Id out of valid range 0-255" );
#undef RESERVE
#define RESERVE(id) static_assert(id>=0 && id<MAX_FLAGS,"Id out of valid range 0-255" );
#undef FREE
#define FREE(id) static_assert(id>=0 && id<MAX_FLAGS,"Id out of valid range 0-255" );
#undef SPEED
#define SPEED(speed) static_assert(speed>=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"
#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
@@ -396,6 +468,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),

View File

@@ -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

View File

@@ -1 +1 @@
#define GITHUB_SHA "devel-202401100719Z"
#define GITHUB_SHA "devel-202402071454Z"

View File

@@ -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
#endif

View File

@@ -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!

View File

@@ -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<firstDevPin;
if (!noOverlap) {
DIAG(F("WARNING HAL Overlap, redefinition of Vpins %u to %u ignored."),
if (!silent) DIAG(F("WARNING HAL Overlap, redefinition of Vpins %u to %u ignored."),
firstPin, lastPin);
return false;
}
}
// Check for overlapping I2C address
if (i2cAddress && dev->_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;
}
}

View File

@@ -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.

View File

@@ -1,5 +1,6 @@
/*
* © 2022, Peter Cole. All rights reserved.
* © 2024, Harald Barth. All rights reserved.
*
* This file is part of EX-CommandStation
*
@@ -100,8 +101,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 +124,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 {
@@ -241,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;
@@ -249,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,
@@ -364,14 +380,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

805
IO_I2CDFPlayer.h Normal file
View File

@@ -0,0 +1,805 @@
/*
* © 2023, Neil McKechnie. All rights reserved.
*
* This file is part of DCC++EX API
*
* This is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* It is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/
/*
* 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 = 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
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 DF_PLAY:
_playCmd = true;
_volCmd = true;
_requestedSong = value;
_requestedVolumeLevel = volume;
_playing = true;
break;
case DF_VOL:
_volCmd = true;
_requestedVolumeLevel = volume;
break;
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
} else {
_requestedFolder = volume;
}
break;
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);
#endif
_repeatCmd = true;
_requestedSong = value;
_requestedVolumeLevel = volume;
_playing = true;
}
break;
case DF_STOPPLAY:
_stopplayCmd = true;
break;
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 = DF_NORMAL;
} else { // Valid EQ parameter range
_requestedEQValue = volume;
}
break;
case DF_RESET:
_resetCmd = true;
break;
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 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);
#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<uint8_t>(arg >> 8),
//static_cast<uint8_t>(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
// Declared in this scope
enum : uint8_t{
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 // IO_I2CDFPlayer_h

57
KeywordHasher.h Normal file
View File

@@ -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 <https://www.gnu.org/licenses/>.
*/
/* 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 <Arduino.h>
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,"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

View File

@@ -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];
@@ -235,13 +221,20 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
gpio_reset_pin((gpio_num_t)p.invpin);
}
#ifdef BOOSTER_INPUT
#ifdef ARDUINO_ESP32S3_DEV
#define LOOP_IDX SIG_IN_FUNC212_IDX //pads 208 to 212 available as loopback
#else
#define LOOP_IDX SIG_IN_FUNC228_IDX //pads 224 to 228 available as loopback
#endif
if (mode & TRACK_MODE_BOOST) {
//DIAG(F("Track=%c mode boost pin %d"),trackToSet+'A', p.pin);
pinMode(BOOSTER_INPUT, INPUT);
gpio_matrix_in(26, SIG_IN_FUNC228_IDX, false); //pads 224 to 228 available as loopback
gpio_matrix_out(p.pin, SIG_IN_FUNC228_IDX, false, false);
gpio_matrix_in(26, LOOP_IDX, false);
gpio_matrix_out(p.pin, LOOP_IDX, false, false);
if (p.invpin != UNUSED_PIN) {
gpio_matrix_out(p.invpin, SIG_IN_FUNC228_IDX, true /*inverted*/, false);
gpio_matrix_out(p.invpin, LOOP_IDX, true /*inverted*/, false);
}
} else // elseif clause continues
#endif
@@ -362,38 +355,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;

View File

@@ -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);
}

View File

@@ -39,9 +39,15 @@
#include "soc/timer_group_reg.h"
void feedTheDog0(){
// feed dog 0
#ifdef ARDUINO_ESP32S3_DEV
TIMERG0.wdtwprotect.wdt_wkey=0x50D83AA1; //MWDT_LL_WKEY_VALUE? write enable
TIMERG0.wdtfeed.wdt_feed=1; // feed dog
TIMERG0.wdtwprotect.wdt_wkey=0; // write protect
#else
TIMERG0.wdt_wprotect=TIMG_WDT_WKEY_VALUE; // write enable
TIMERG0.wdt_feed=1; // feed dog
TIMERG0.wdt_wprotect=0; // write protect
#endif
// feed dog 1
//TIMERG1.wdt_wprotect=TIMG_WDT_WKEY_VALUE; // write enable
//TIMERG1.wdt_feed=1; // feed dog
@@ -164,6 +170,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 +212,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 +236,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;

View File

@@ -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,31 @@ 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.
// I2C address range 0x48 - 0x57
//
// 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.
//=======================================================================

View File

@@ -12,7 +12,6 @@
default_envs =
mega2560
uno
mega328
unowifiR2
nano
samd21-dev-usb

View File

@@ -3,7 +3,23 @@
#include "StringFormatter.h"
#define VERSION "5.2.22"
#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
// - 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
// 5.2.26 - Silently ignore overridden HAL defaults
// - include HAL_IGNORE_DEFAULTS macro in EXRAIL
// 5.2.25 - Fix bug causing <X> after working <D commands
// 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
// 5.2.20 - Check return of Ethernet.begin()