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

Compare commits

..

1 Commits

Author SHA1 Message Date
Kcsmith0708
9e9586ddee
Merge 183b824a5d into 6d0740eab4 2024-01-29 22:55:29 +01:00
28 changed files with 32 additions and 1213 deletions

51
DCC.cpp
View File

@ -278,57 +278,6 @@ void DCC::setAccessory(int address, byte port, bool gate, byte onoff /*= 2*/) {
} }
} }
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.
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
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 > 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 // 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);
return true;
}
// //
// writeCVByteMain: Write a byte with PoM on main. This writes // writeCVByteMain: Write a byte with PoM on main. This writes
// the 5 byte sized packet to implement this DCC function // the 5 byte sized packet to implement this DCC function

1
DCC.h
View File

@ -71,7 +71,6 @@ public:
static uint32_t getFunctionMap(int cab); static uint32_t getFunctionMap(int cab);
static void updateGroupflags(byte &flags, int16_t functionNumber); static void updateGroupflags(byte &flags, int16_t functionNumber);
static void setAccessory(int address, byte port, bool gate, byte onoff = 2); static void setAccessory(int address, byte port, bool gate, byte onoff = 2);
static bool setExtendedAccessory(int16_t address, int16_t value, byte repeats=3);
static bool writeTextPacket(byte *b, int nBytes); static bool writeTextPacket(byte *b, int nBytes);
// ACKable progtrack calls bitresults callback 0,0 or -1, cv returns value or -1 // ACKable progtrack calls bitresults callback 0,0 or -1, cv returns value or -1

View File

@ -45,7 +45,7 @@ Once a new OPCODE is decided upon, update this list.
0, Track power off 0, Track power off
1, Track power on 1, Track power on
a, DCC accessory control a, DCC accessory control
A, DCC extended accessory control A,
b, Write CV bit on main b, Write CV bit on main
B, Write CV bit B, Write CV bit
c, Request current command c, Request current command
@ -385,13 +385,6 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
} }
return; return;
case 'A': // EXTENDED ACCESSORY <A address value>
// 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 <T ...> case 'T': // TURNOUT <T ...>
if (parseT(stream, params, p)) if (parseT(stream, params, p))
return; return;
@ -1042,32 +1035,7 @@ bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) {
DCC::setGlobalSpeedsteps(128); DCC::setGlobalSpeedsteps(128);
DIAG(F("128 Speedsteps")); DIAG(F("128 Speedsteps"));
return true; return true;
#if defined(HAS_ENOUGH_MEMORY) && !defined(ARDUINO_ARCH_UNO)
case "RAILCOM"_hk:
{ // <C RAILCOM ON|OFF|DEBUG >
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(on,debug)?F("ON"):F("OFF"));
return true;
}
#endif
#ifndef DISABLE_PROG #ifndef DISABLE_PROG
case "ACK"_hk: // <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 (params >= 3) {

View File

@ -62,8 +62,6 @@ class DCCTimer {
static bool isPWMPin(byte pin); static bool isPWMPin(byte pin);
static void setPWM(byte pin, bool high); static void setPWM(byte pin, bool high);
static void clearPWM(); static void clearPWM();
static void startRailcomTimer(byte brakePin);
static void ackRailcomTimer();
static void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency); static void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency);
static void DCCEXanalogWrite(uint8_t pin, int value); static void DCCEXanalogWrite(uint8_t pin, int value);

View File

@ -39,9 +39,6 @@ INTERRUPT_CALLBACK interruptHandler=0;
#define TIMER1_A_PIN 11 #define TIMER1_A_PIN 11
#define TIMER1_B_PIN 12 #define TIMER1_B_PIN 12
#define TIMER1_C_PIN 13 #define TIMER1_C_PIN 13
#define TIMER2_A_PIN 10
#define TIMER2_B_PIN 9
#else #else
#define TIMER1_A_PIN 9 #define TIMER1_A_PIN 9
#define TIMER1_B_PIN 10 #define TIMER1_B_PIN 10
@ -58,67 +55,6 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
interrupts(); 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.)
*/
(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)
TCCR2A = 0; // Clear Timer2 control register A
TCCR2B = 0; // Clear Timer2 control register B
TCNT2 = 0; // Initialize Timer2 counter value to 0
// Configure Phase and Frequency Correct PWM mode
TCCR2A = (1 << COM2B1); // enable pwm on pin 9
TCCR2A |= (1 << WGM20);
// Set Timer 2 prescaler to 32
TCCR2B = (1 << CS21) | (1 << CS20); // 32 prescaler
// Set the compare match value for desired interval
OCR2A = (F_CPU / 1000000) * cutoutDuration / 64 - 1;
// Calculate the compare match value for desired duty cycle
OCR2B = OCR2A+1; // set duty cycle to 100%= OCR2A)
// Enable Timer2 output on pin 9 (OC2B)
DDRB |= (1 << DDB1);
// TODO Fudge TCNT2 to sync with last tcnt1 tick + 28uS
// 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; // brake pin pwm duty cycle 0 at next tick
}
// ISR called by timer interrupt every 58uS // ISR called by timer interrupt every 58uS
ISR(TIMER1_OVF_vect){ interruptHandler(); } ISR(TIMER1_OVF_vect){ interruptHandler(); }

View File

@ -80,15 +80,6 @@ extern char *__malloc_heap_start;
interruptHandler(); interruptHandler();
} }
void DCCTimer::startRailcomTimer(byte brakePin) {
// TODO: for intended operation see DCCTimerAVR.cpp
(void) brakePin;
}
void DCCTimer::ackRailcomTimer() {
// TODO: for intended operation see DCCTimerAVR.cpp
}
bool DCCTimer::isPWMPin(byte pin) { bool DCCTimer::isPWMPin(byte pin) {
(void) pin; (void) pin;
return false; // TODO what are the relevant pins? return false; // TODO what are the relevant pins?

View File

@ -76,15 +76,6 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
interrupts(); interrupts();
} }
void DCCTimer::startRailcomTimer(byte brakePin) {
// TODO: for intended operation see DCCTimerAVR.cpp
(void) brakePin;
}
void DCCTimer::ackRailcomTimer() {
// TODO: for intended operation see DCCTimerAVR.cpp
}
// Timer IRQ handlers replace the dummy handlers (in cortex_handlers) // Timer IRQ handlers replace the dummy handlers (in cortex_handlers)
// copied from rf24 branch // copied from rf24 branch
void TCC0_Handler() { void TCC0_Handler() {

View File

@ -201,15 +201,6 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
interrupts(); interrupts();
} }
void DCCTimer::startRailcomTimer(byte brakePin) {
// TODO: for intended operation see DCCTimerAVR.cpp
(void) brakePin;
}
void DCCTimer::ackRailcomTimer() {
// TODO: for intended operation see DCCTimerAVR.cpp
}
bool DCCTimer::isPWMPin(byte pin) { bool DCCTimer::isPWMPin(byte pin) {
//TODO: STM32 whilst this call to digitalPinHasPWM will reveal which pins can do PWM, //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 // there's no support yet for High Accuracy, so for now return false

View File

@ -39,15 +39,6 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
myDCCTimer.begin(interruptHandler, DCC_SIGNAL_TIME); myDCCTimer.begin(interruptHandler, DCC_SIGNAL_TIME);
} }
void DCCTimer::startRailcomTimer(byte brakePin) {
// TODO: for intended operation see DCCTimerAVR.cpp
(void) brakePin;
}
void DCCTimer::ackRailcomTimer() {
// TODO: for intended operation see DCCTimerAVR.cpp
}
bool DCCTimer::isPWMPin(byte pin) { bool DCCTimer::isPWMPin(byte pin) {
//Teensy: digitalPinHasPWM, todo //Teensy: digitalPinHasPWM, todo
(void) pin; (void) pin;

View File

@ -116,21 +116,7 @@ DCCWaveform::DCCWaveform( byte preambleBits, bool isMain) {
bits_sent = 0; bits_sent = 0;
} }
volatile bool DCCWaveform::railcomActive=false; // switched on by user
volatile bool DCCWaveform::railcomDebug=false; // switched on by user
bool DCCWaveform::setRailcom(bool on, bool debug) {
if (on) {
// TODO check possible
railcomActive=true;
railcomDebug=debug;
}
else {
railcomActive=false;
railcomDebug=false;
}
return railcomActive;
}
#pragma GCC push_options #pragma GCC push_options
#pragma GCC optimize ("-O3") #pragma GCC optimize ("-O3")
@ -138,6 +124,7 @@ void DCCWaveform::interrupt2() {
// calculate the next bit to be sent: // calculate the next bit to be sent:
// set state WAVE_MID_1 for a 1=bit // set state WAVE_MID_1 for a 1=bit
// or WAVE_HIGH_0 for a 0 bit. // or WAVE_HIGH_0 for a 0 bit.
if (remainingPreambles > 0 ) { if (remainingPreambles > 0 ) {
state=WAVE_MID_1; // switch state to trigger LOW on next interrupt state=WAVE_MID_1; // switch state to trigger LOW on next interrupt
remainingPreambles--; remainingPreambles--;
@ -147,7 +134,6 @@ void DCCWaveform::interrupt2() {
// that the reminder doesn't block a more urgent packet. // that the reminder doesn't block a more urgent packet.
reminderWindowOpen=transmitRepeats==0 && remainingPreambles<4 && remainingPreambles>1; reminderWindowOpen=transmitRepeats==0 && remainingPreambles<4 && remainingPreambles>1;
if (remainingPreambles==1) promotePendingPacket(); 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. // 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. // Allow for checkAck and its called functions using 22 bytes more.
else DCCTimer::updateMinimumFreeMemoryISR(22); else DCCTimer::updateMinimumFreeMemoryISR(22);
@ -171,12 +157,6 @@ void DCCWaveform::interrupt2() {
bytes_sent = 0; bytes_sent = 0;
// preamble for next packet will start... // preamble for next packet will start...
remainingPreambles = requiredPreambles; 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);
} }
} }
} }
@ -228,11 +208,7 @@ void DCCWaveform::promotePendingPacket() {
// nothing to do, just send idles or resets // nothing to do, just send idles or resets
// Fortunately reset and idle packets are the same length // Fortunately reset and idle packets are the same length
// Note: If railcomDebug is on, then we send resets to the main memcpy( transmitPacket, isMainTrack ? idlePacket : resetPacket, sizeof(idlePacket));
// 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); transmitLength = sizeof(idlePacket);
transmitRepeats = 0; transmitRepeats = 0;
if (getResets() < 250) sentResetsSincePacket++; // only place to increment (private!) if (getResets() < 250) sentResetsSincePacket++; // only place to increment (private!)
@ -321,10 +297,4 @@ bool DCCWaveform::isReminderWindowOpen() {
void IRAM_ATTR DCCWaveform::loop() { void IRAM_ATTR DCCWaveform::loop() {
DCCACK::checkAck(progTrack.getResets()); DCCACK::checkAck(progTrack.getResets());
} }
bool DCCWaveform::setRailcom(bool on, bool debug) {
// TODO... ESP32 railcom waveform
return false;
}
#endif #endif

View File

@ -40,14 +40,7 @@ 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 // The WAVE_STATE enum is deliberately numbered because a change of order would be catastrophic
// to the transform array. // to the transform array.
enum WAVE_STATE : byte { 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};
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 // NOTE: static functions are used for the overall controller, then
// one instance is created for each track. // one instance is created for each track.
@ -85,8 +78,6 @@ class DCCWaveform {
void schedulePacket(const byte buffer[], byte byteCount, byte repeats); void schedulePacket(const byte buffer[], byte byteCount, byte repeats);
bool isReminderWindowOpen(); bool isReminderWindowOpen();
void promotePendingPacket(); void promotePendingPacket();
static bool setRailcom(bool on, bool debug);
static bool isRailcom() {return railcomActive;}
private: private:
#ifndef ARDUINO_ARCH_ESP32 #ifndef ARDUINO_ARCH_ESP32
@ -112,9 +103,6 @@ class DCCWaveform {
byte pendingPacket[MAX_PACKET_SIZE+1]; // +1 for checksum byte pendingPacket[MAX_PACKET_SIZE+1]; // +1 for checksum
byte pendingLength; byte pendingLength;
byte pendingRepeats; byte pendingRepeats;
static volatile bool railcomActive; // switched on by user
static volatile bool railcomDebug; // switched on by user
#ifdef ARDUINO_ARCH_ESP32 #ifdef ARDUINO_ARCH_ESP32
static RMTChannel *rmtMainChannel; static RMTChannel *rmtMainChannel;
static RMTChannel *rmtProgChannel; static RMTChannel *rmtProgChannel;

View File

@ -800,14 +800,6 @@ void RMFT2::loop2() {
DCC::setAccessory(addr,subaddr,active); DCC::setAccessory(addr,subaddr,active);
break; break;
} }
case OPCODE_ASPECT: {
// operand is address<<5 | value
int16_t address=operand>>5;
byte aspect=operand & 0x1f;
if (!signalAspectEvent(address,aspect))
DCC::setExtendedAccessory(address,aspect);
break;
}
case OPCODE_FOLLOW: case OPCODE_FOLLOW:
progCounter=routeLookup->find(operand); progCounter=routeLookup->find(operand);
@ -1069,7 +1061,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
if (diag) DIAG(F(" doSignal %d %x"),id,rag); if (diag) DIAG(F(" doSignal %d %x"),id,rag);
// Schedule any event handler for this signal change. // Schedule any event handler for this signal change.
// This will work even without a signal definition. // Thjis will work even without a signal definition.
if (rag==SIGNAL_RED) onRedLookup->handleEvent(F("RED"),id); if (rag==SIGNAL_RED) onRedLookup->handleEvent(F("RED"),id);
else if (rag==SIGNAL_GREEN) onGreenLookup->handleEvent(F("GREEN"),id); else if (rag==SIGNAL_GREEN) onGreenLookup->handleEvent(F("GREEN"),id);
else onAmberLookup->handleEvent(F("AMBER"),id); else onAmberLookup->handleEvent(F("AMBER"),id);
@ -1106,16 +1098,6 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
return; 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) // LED or similar 3 pin signal, (all pins zero would be a virtual signal)
// If amberpin is zero, synthesise amber from red+green // If amberpin is zero, synthesise amber from red+green
const byte SIMAMBER=0x00; const byte SIMAMBER=0x00;
@ -1149,38 +1131,6 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
return (flags[sigslot] & SIGNAL_MASK) == rag; 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) { void RMFT2::turnoutEvent(int16_t turnoutId, bool closed) {
// Hunt for an ONTHROW/ONCLOSE for this turnout // Hunt for an ONTHROW/ONCLOSE for this turnout
if (closed) onCloseLookup->handleEvent(F("CLOSE"),turnoutId); if (closed) onCloseLookup->handleEvent(F("CLOSE"),turnoutId);

View File

@ -54,7 +54,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,
OPCODE_START,OPCODE_SETLOCO,OPCODE_SENDLOCO,OPCODE_FORGET, OPCODE_START,OPCODE_SETLOCO,OPCODE_SENDLOCO,OPCODE_FORGET,
OPCODE_PAUSE, OPCODE_RESUME,OPCODE_POWEROFF,OPCODE_POWERON, OPCODE_PAUSE, OPCODE_RESUME,OPCODE_POWEROFF,OPCODE_POWERON,
OPCODE_ONCLOSE, OPCODE_ONTHROW, OPCODE_SERVOTURNOUT, OPCODE_PINTURNOUT, OPCODE_ONCLOSE, OPCODE_ONTHROW, OPCODE_SERVOTURNOUT, OPCODE_PINTURNOUT,
OPCODE_PRINT,OPCODE_DCCACTIVATE,OPCODE_ASPECT, OPCODE_PRINT,OPCODE_DCCACTIVATE,
OPCODE_ONACTIVATE,OPCODE_ONDEACTIVATE, OPCODE_ONACTIVATE,OPCODE_ONDEACTIVATE,
OPCODE_ROSTER,OPCODE_KILLALL, OPCODE_ROSTER,OPCODE_KILLALL,
OPCODE_ROUTE,OPCODE_AUTOMATION,OPCODE_SEQUENCE, OPCODE_ROUTE,OPCODE_AUTOMATION,OPCODE_SEQUENCE,
@ -155,11 +155,9 @@ class LookList {
static void clockEvent(int16_t clocktime, bool change); static void clockEvent(int16_t clocktime, bool change);
static void rotateEvent(int16_t id, bool change); static void rotateEvent(int16_t id, bool change);
static void powerEvent(int16_t track, bool overload); 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 SERVO_SIGNAL_FLAG=0x4000;
static const int16_t ACTIVE_HIGH_SIGNAL_FLAG=0x2000; static const int16_t ACTIVE_HIGH_SIGNAL_FLAG=0x2000;
static const int16_t DCC_SIGNAL_FLAG=0x1000; static const int16_t DCC_SIGNAL_FLAG=0x1000;
static const int16_t DCCX_SIGNAL_FLAG=0x3000;
static const int16_t SIGNAL_ID_MASK=0x0FFF; static const int16_t SIGNAL_ID_MASK=0x0FFF;
// Throttle Info Access functions built by exrail macros // Throttle Info Access functions built by exrail macros
static const byte rosterNameCount; static const byte rosterNameCount;
@ -260,23 +258,4 @@ private:
#define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter) #define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter)
#define SKIPOP progCounter+=3 #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 #endif

View File

@ -31,7 +31,6 @@
#undef ALIAS #undef ALIAS
#undef AMBER #undef AMBER
#undef ANOUT #undef ANOUT
#undef ASPECT
#undef AT #undef AT
#undef ATGTE #undef ATGTE
#undef ATLT #undef ATLT
@ -43,9 +42,7 @@
#undef CLEAR_STASH #undef CLEAR_STASH
#undef CLEAR_ALL_STASH #undef CLEAR_ALL_STASH
#undef CLOSE #undef CLOSE
#undef CONFIGURE_SERVO
#undef DCC_SIGNAL #undef DCC_SIGNAL
#undef DCCX_SIGNAL
#undef DCC_TURNTABLE #undef DCC_TURNTABLE
#undef DEACTIVATE #undef DEACTIVATE
#undef DEACTIVATEL #undef DEACTIVATEL
@ -87,7 +84,6 @@
#undef IFTTPOSITION #undef IFTTPOSITION
#undef IFRE #undef IFRE
#undef INVERT_DIRECTION #undef INVERT_DIRECTION
#undef JMRI_SENSOR
#undef JOIN #undef JOIN
#undef KILLALL #undef KILLALL
#undef LATCH #undef LATCH
@ -188,7 +184,6 @@
#define AMBER(signal_id) #define AMBER(signal_id)
#define ANOUT(vpin,value,param1,param2) #define ANOUT(vpin,value,param1,param2)
#define AT(sensor_id) #define AT(sensor_id)
#define ASPECT(address,value)
#define ATGTE(sensor_id,value) #define ATGTE(sensor_id,value)
#define ATLT(sensor_id,value) #define ATLT(sensor_id,value)
#define ATTIMEOUT(sensor_id,timeout_ms) #define ATTIMEOUT(sensor_id,timeout_ms)
@ -199,9 +194,7 @@
#define CLEAR_STASH(id) #define CLEAR_STASH(id)
#define CLEAR_ALL_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_SIGNAL(id,add,subaddr)
#define DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect)
#define DCC_TURNTABLE(id,home,description) #define DCC_TURNTABLE(id,home,description)
#define DEACTIVATE(addr,subaddr) #define DEACTIVATE(addr,subaddr)
#define DEACTIVATEL(addr) #define DEACTIVATEL(addr)
@ -243,7 +236,6 @@
#define IFTTPOSITION(turntable_id,position) #define IFTTPOSITION(turntable_id,position)
#define IFRE(sensor_id,value) #define IFRE(sensor_id,value)
#define INVERT_DIRECTION #define INVERT_DIRECTION
#define JMRI_SENSOR(vpin,count...)
#define JOIN #define JOIN
#define KILLALL #define KILLALL
#define LATCH(sensor_id) #define LATCH(sensor_id)

View File

@ -51,14 +51,6 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16
opcode=0; opcode=0;
break; break;
case 'A': // <A address aspect>
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': case 'L':
// This entire code block is compiled out if LLC macros not used // This entire code block is compiled out if LLC macros not used
if (!(compileFeatures & FEATURE_LCC)) return; if (!(compileFeatures & FEATURE_LCC)) return;

View File

@ -59,10 +59,6 @@
// helper macro for turnout description as HIDDEN // helper macro for turnout description as HIDDEN
#define HIDDEN "\x01" #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 // helper macro to strip leading zeros off time inputs
// (10#mins)%100) // (10#mins)%100)
#define STRIP_ZERO(value) 10##value%100 #define STRIP_ZERO(value) 10##value%100
@ -117,9 +113,6 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU
// - check range on LATCH/UNLATCH // - check range on LATCH/UNLATCH
// This pass generates no runtime data or code // This pass generates no runtime data or code
#include "EXRAIL2MacroReset.h" #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 #undef CALL
#define CALL(id) static_assert(hasseq(id),"Sequence not found"); #define CALL(id) static_assert(hasseq(id),"Sequence not found");
#undef FOLLOW #undef FOLLOW
@ -152,10 +145,6 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU
#define HAL(haltype,params...) haltype::create(params); #define HAL(haltype,params...) haltype::create(params);
#undef HAL_IGNORE_DEFAULTS #undef HAL_IGNORE_DEFAULTS
#define HAL_IGNORE_DEFAULTS ignore_defaults=true; #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 exrailHalSetup() {
bool ignore_defaults=false; bool ignore_defaults=false;
#include "myAutomation.h" #include "myAutomation.h"
@ -172,8 +161,6 @@ bool exrailHalSetup() {
#define SERVO_SIGNAL(vpin,redval,amberval,greenval) | FEATURE_SIGNAL #define SERVO_SIGNAL(vpin,redval,amberval,greenval) | FEATURE_SIGNAL
#undef DCC_SIGNAL #undef DCC_SIGNAL
#define DCC_SIGNAL(id,addr,subaddr) | FEATURE_SIGNAL #define DCC_SIGNAL(id,addr,subaddr) | FEATURE_SIGNAL
#undef DCCX_SIGNAL
#define DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect) | FEATURE_SIGNAL
#undef VIRTUAL_SIGNAL #undef VIRTUAL_SIGNAL
#define VIRTUAL_SIGNAL(id) | FEATURE_SIGNAL #define VIRTUAL_SIGNAL(id) | FEATURE_SIGNAL
@ -403,8 +390,6 @@ const FSH * RMFT2::getRosterFunctions(int16_t id) {
#define SERVO_SIGNAL(vpin,redval,amberval,greenval) vpin | RMFT2::SERVO_SIGNAL_FLAG,redval,amberval,greenval, #define SERVO_SIGNAL(vpin,redval,amberval,greenval) vpin | RMFT2::SERVO_SIGNAL_FLAG,redval,amberval,greenval,
#undef DCC_SIGNAL #undef DCC_SIGNAL
#define DCC_SIGNAL(id,addr,subaddr) id | RMFT2::DCC_SIGNAL_FLAG,addr,subaddr,0, #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 #undef VIRTUAL_SIGNAL
#define VIRTUAL_SIGNAL(id) id,0,0,0, #define VIRTUAL_SIGNAL(id) id,0,0,0,
@ -439,7 +424,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define ALIAS(name,value...) #define ALIAS(name,value...)
#define AMBER(signal_id) OPCODE_AMBER,V(signal_id), #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 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 AT(sensor_id) OPCODE_AT,V(sensor_id),
#define ATGTE(sensor_id,value) OPCODE_ATGTE,V(sensor_id),OPCODE_PAD,V(value), #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), #define ATLT(sensor_id,value) OPCODE_ATLT,V(sensor_id),OPCODE_PAD,V(value),
@ -451,7 +435,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define CLEAR_STASH(id) OPCODE_CLEAR_STASH,V(id), #define CLEAR_STASH(id) OPCODE_CLEAR_STASH,V(id),
#define CLEAR_ALL_STASH OPCODE_CLEAR_ALL_STASH,V(0), #define CLEAR_ALL_STASH OPCODE_CLEAR_ALL_STASH,V(0),
#define CLOSE(id) OPCODE_CLOSE,V(id), #define CLOSE(id) OPCODE_CLOSE,V(id),
#define CONFIGURE_SERVO(vpin,pos1,pos2,profile)
#ifndef IO_NO_HAL #ifndef IO_NO_HAL
#define DCC_TURNTABLE(id,home,description...) OPCODE_DCCTURNTABLE,V(id),OPCODE_PAD,V(home), #define DCC_TURNTABLE(id,home,description...) OPCODE_DCCTURNTABLE,V(id),OPCODE_PAD,V(home),
#endif #endif
@ -461,7 +444,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define DELAYMINS(mindelay) OPCODE_DELAYMINS,V(mindelay), #define DELAYMINS(mindelay) OPCODE_DELAYMINS,V(mindelay),
#define DELAYRANDOM(mindelay,maxdelay) DELAY(mindelay) OPCODE_RANDWAIT,V((maxdelay-mindelay)/100L), #define DELAYRANDOM(mindelay,maxdelay) DELAY(mindelay) OPCODE_RANDWAIT,V((maxdelay-mindelay)/100L),
#define DCC_SIGNAL(id,add,subaddr) #define DCC_SIGNAL(id,add,subaddr)
#define DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect)
#define DONE OPCODE_ENDTASK,0,0, #define DONE OPCODE_ENDTASK,0,0,
#define DRIVE(analogpin) OPCODE_DRIVE,V(analogpin), #define DRIVE(analogpin) OPCODE_DRIVE,V(analogpin),
#define ELSE OPCODE_ELSE,0,0, #define ELSE OPCODE_ELSE,0,0,
@ -501,7 +483,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#endif #endif
#define IFRE(sensor_id,value) OPCODE_IFRE,V(sensor_id),OPCODE_PAD,V(value), #define IFRE(sensor_id,value) OPCODE_IFRE,V(sensor_id),OPCODE_PAD,V(value),
#define INVERT_DIRECTION OPCODE_INVERT_DIRECTION,0,0, #define INVERT_DIRECTION OPCODE_INVERT_DIRECTION,0,0,
#define JMRI_SENSOR(vpin,count...)
#define JOIN OPCODE_JOIN,0,0, #define JOIN OPCODE_JOIN,0,0,
#define KILLALL OPCODE_KILLALL,0,0, #define KILLALL OPCODE_KILLALL,0,0,
#define LATCH(sensor_id) OPCODE_LATCH,V(sensor_id), #define LATCH(sensor_id) OPCODE_LATCH,V(sensor_id),

View File

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

View File

@ -54,8 +54,6 @@ static const FSH * guessI2CDeviceType(uint8_t address) {
return F("Time-of-flight sensor"); return F("Time-of-flight sensor");
else if (address >= 0x3c && address <= 0x3d) else if (address >= 0x3c && address <= 0x3d)
return F("OLED Display"); return F("OLED Display");
else if (address >= 0x48 && address <= 0x57) // SC16IS752x UART detection
return F("SC16IS75x UART");
else if (address >= 0x48 && address <= 0x4f) else if (address >= 0x48 && address <= 0x4f)
return F("Analogue Inputs or PWM"); return F("Analogue Inputs or PWM");
else if (address >= 0x40 && address <= 0x4f) else if (address >= 0x40 && address <= 0x4f)

View File

@ -1,805 +0,0 @@
/*
* © 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

View File

@ -230,13 +230,6 @@ Sensor *Sensor::create(int snum, VPIN pin, int pullUp){
return tt; return tt;
} }
// Creet multiple eponymous sensors based on vpin alone.
void Sensor::createMultiple(VPIN firstPin, byte count) {
for (byte i=0;i<count;i++) {
create(firstPin+i,firstPin+i,1);
}
}
/////////////////////////////////////////////////////////////////////////////// ///////////////////////////////////////////////////////////////////////////////
// Object method to directly change the input state, for sensors such as LCN which are updated // Object method to directly change the input state, for sensors such as LCN which are updated
// by means other than by polling an input. // by means other than by polling an input.

View File

@ -76,7 +76,6 @@ public:
static void store(); static void store();
#endif #endif
static Sensor *create(int id, VPIN vpin, int pullUp); static Sensor *create(int id, VPIN vpin, int pullUp);
static void createMultiple(VPIN firstPin, byte count=1);
static Sensor* get(int id); static Sensor* get(int id);
static bool remove(int id); static bool remove(int id);
static void checkAll(); static void checkAll();

View File

@ -157,6 +157,12 @@ void TrackManager::setDCCSignal( bool on) {
HAVE_PORTF(PORTF=shadowPORTF); HAVE_PORTF(PORTF=shadowPORTF);
} }
void TrackManager::setCutout( bool on) {
(void) on;
// TODO Cutout needs fake ports as well
// TODO APPLY_BY_MODE(TRACK_MODE_MAIN,setCutout(on));
}
// setPROGSignal(), called from interrupt context // setPROGSignal(), called from interrupt context
// does assume ports are shadowed if they can be // does assume ports are shadowed if they can be
void TrackManager::setPROGSignal( bool on) { void TrackManager::setPROGSignal( bool on) {

View File

@ -57,6 +57,7 @@ class TrackManager {
); );
static void setDCCSignal( bool on); static void setDCCSignal( bool on);
static void setCutout( bool on);
static void setPROGSignal( bool on); static void setPROGSignal( bool on);
static void setDCSignal(int16_t cab, byte speedbyte); static void setDCSignal(int16_t cab, byte speedbyte);
static MotorDriver * getProgDriver(); static MotorDriver * getProgDriver();

View File

@ -187,7 +187,6 @@ void WiThrottle::parse(RingStream * stream, byte * cmdx) {
} }
break; break;
case 'N': // Heartbeat (2), only send if connection completed by 'HU' message 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 StringFormatter::send(stream, F("*%d\n"), heartrateSent ? HEARTBEAT_SECONDS : HEARTBEAT_PRELOAD); // return timeout value
break; break;
case 'M': // multithrottle case 'M': // multithrottle
@ -195,7 +194,7 @@ void WiThrottle::parse(RingStream * stream, byte * cmdx) {
break; break;
case 'H': // send initial connection info after receiving "HU" message case 'H': // send initial connection info after receiving "HU" message
if (cmd[1] == 'U') { if (cmd[1] == 'U') {
sendIntro(stream); sendIntro(stream);
} }
break; break;
case 'Q': // case 'Q': //
@ -499,14 +498,12 @@ void WiThrottle::getLocoCallback(int16_t locoid) {
} }
void WiThrottle::sendIntro(Print* stream) { void WiThrottle::sendIntro(Print* stream) {
if (introSent) // sendIntro only once
return;
introSent=true; introSent=true;
StringFormatter::send(stream,F("VN2.0\nHTDCC-EX\nRL0\n")); 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("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("PTT]\\[Turnouts}|{Turnout]\\[THROW}|{2]\\[CLOSE}|{4\n"));
StringFormatter::send(stream,F("PPA%x\n"),TrackManager::getMainPower()==POWERMODE::ON); 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!) // 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); StringFormatter::send(stream,F("*%d\nHMConnecting..\n"), HEARTBEAT_PRELOAD);
} }

View File

@ -25,7 +25,6 @@
//#include "IO_EXTurntable.h" // Turntable-EX turntable controller //#include "IO_EXTurntable.h" // Turntable-EX turntable controller
//#include "IO_EXFastClock.h" // FastClock driver //#include "IO_EXFastClock.h" // FastClock driver
//#include "IO_PCA9555.h" // 16-bit I/O expander (NXP & Texas Instruments). //#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. // The function halSetup() is invoked from CS if it exists within the build.
@ -235,31 +234,6 @@ void halSetup() {
// DFPlayer::create(10000, 10, Serial1); // 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. // 16-pad capacitative touch key pad based on TP229 IC.
//======================================================================= //=======================================================================

View File

@ -12,6 +12,7 @@
default_envs = default_envs =
mega2560 mega2560
uno uno
mega328
unowifiR2 unowifiR2
nano nano
samd21-dev-usb samd21-dev-usb
@ -148,7 +149,10 @@ build_flags =
platform = atmelavr platform = atmelavr
board = uno board = uno
framework = arduino framework = arduino
lib_deps = ${env.lib_deps} lib_deps =
${env.lib_deps}
arduino-libraries/Ethernet
SPI
monitor_speed = 115200 monitor_speed = 115200
monitor_echo = yes monitor_echo = yes
build_flags = -mcall-prologues build_flags = -mcall-prologues
@ -161,7 +165,6 @@ framework = arduino
lib_deps = ${env.lib_deps} lib_deps = ${env.lib_deps}
monitor_speed = 115200 monitor_speed = 115200
monitor_echo = yes monitor_echo = yes
build_flags = -mcall-prologues
[env:ESP32] [env:ESP32]
platform = espressif32 platform = espressif32

View File

@ -3,20 +3,7 @@
#include "StringFormatter.h" #include "StringFormatter.h"
#define VERSION "5.2.35" #define VERSION "5.2.28"
// 5.2.35 - Bugfix: Make DCC Extended Accessories follow RCN-213
// 5.2.34 - <A address aspect> Command fopr DCC Extended Accessories
// - Exrail ASPECT(address,aspect) for above.
// - EXRAIL DCCX_SIGNAL(Address,redAspect,amberAspect,greenAspect)
// - Exrail intercept <A ...> 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 <S> 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
// - Added UART detection to I2CManager.cpp
// 5.2.28 - ESP32: Can all Wifi channels. // 5.2.28 - ESP32: Can all Wifi channels.
// - ESP32: Only write Wifi password to display if it is a well known one // - ESP32: Only write Wifi password to display if it is a well known one
// 5.2.27 - Bugfix: IOExpander memory allocation // 5.2.27 - Bugfix: IOExpander memory allocation