diff --git a/CommandStation-EX.ino b/CommandStation-EX.ino
index 80d8b4e..08b0ae2 100644
--- a/CommandStation-EX.ino
+++ b/CommandStation-EX.ino
@@ -63,7 +63,12 @@ void setup()
// Responsibility 1: Start the usb connection for diagnostics
// This is normally Serial but uses SerialUSB on a SAMD processor
+
SerialManager::init();
+// Serial.begin(115200); // check this -- removed when resolve conflicts
+#ifdef ESP_DEBUG
+ Serial.setDebugOutput(true);
+#endif
DIAG(F("License GPLv3 fsf.org (c) dcc-ex.com"));
@@ -77,9 +82,12 @@ void setup()
// Start the WiFi interface on a MEGA, Uno cannot currently handle WiFi
// Start Ethernet if it exists
#if WIFI_ON
+#ifndef ESP_FAMILY
WifiInterface::setup(WIFI_SERIAL_LINK_SPEED, F(WIFI_SSID), F(WIFI_PASSWORD), F(WIFI_HOSTNAME), IP_PORT, WIFI_CHANNEL);
+#else
+ WifiESP::setup(WIFI_SSID, WIFI_PASSWORD, WIFI_HOSTNAME, IP_PORT, WIFI_CHANNEL);
+#endif
#endif // WIFI_ON
-
#if ETHERNET_ON
EthernetInterface::setup();
#endif // ETHERNET_ON
@@ -119,14 +127,17 @@ void loop()
// Responsibility 1: Handle DCC background processes
// (loco reminders and power checks)
DCC::loop();
-
// Responsibility 2: handle any incoming commands on USB connection
SerialManager::loop();
// Responsibility 3: Optionally handle any incoming WiFi traffic
#if WIFI_ON
+#ifndef ESP_FAMILY
WifiInterface::loop();
+#else
+ WifiESP::loop();
#endif
+#endif //WIFI_ON
#if ETHERNET_ON
EthernetInterface::loop();
#endif
@@ -145,8 +156,10 @@ void loop()
Sensor::checkAll(); // Update and print changes
// Report any decrease in memory (will automatically trigger on first call)
- static int ramLowWatermark = __INT_MAX__; // replaced on first loop
-
+ static int ramLowWatermark = __INT_MAX__; // replaced on first loop
+#ifdef ESP_FAMILY
+ updateMinimumFreeMemory(128);
+#endif
int freeNow = minimumFreeMemory();
if (freeNow < ramLowWatermark) {
ramLowWatermark = freeNow;
diff --git a/DCC.cpp b/DCC.cpp
index 6674fb9..b8cc12a 100644
--- a/DCC.cpp
+++ b/DCC.cpp
@@ -313,14 +313,14 @@ const ackOp FLASH WRITE_BIT0_PROG[] = {
W0,WACK,
V0, WACK, // validate bit is 0
ITC1, // if acked, callback(1)
- FAIL // callback (-1)
+ CALLFAIL // callback (-1)
};
const ackOp FLASH WRITE_BIT1_PROG[] = {
BASELINE,
W1,WACK,
V1, WACK, // validate bit is 1
ITC1, // if acked, callback(1)
- FAIL // callback (-1)
+ CALLFAIL // callback (-1)
};
const ackOp FLASH VERIFY_BIT0_PROG[] = {
@@ -328,8 +328,8 @@ const ackOp FLASH VERIFY_BIT0_PROG[] = {
V0, WACK, // validate bit is 0
ITC0, // if acked, callback(0)
V1, WACK, // validate bit is 1
- ITC1,
- FAIL // callback (-1)
+ ITC1,
+ CALLFAIL // callback (-1)
};
const ackOp FLASH VERIFY_BIT1_PROG[] = {
BASELINE,
@@ -337,7 +337,7 @@ const ackOp FLASH VERIFY_BIT1_PROG[] = {
ITC1, // if acked, callback(1)
V0, WACK,
ITC0,
- FAIL // callback (-1)
+ CALLFAIL // callback (-1)
};
const ackOp FLASH READ_BIT_PROG[] = {
@@ -346,15 +346,15 @@ const ackOp FLASH READ_BIT_PROG[] = {
ITC1, // if acked, callback(1)
V0, WACK, // validate bit is zero
ITC0, // if acked callback 0
- FAIL // bit not readable
+ CALLFAIL // bit not readable
};
const ackOp FLASH WRITE_BYTE_PROG[] = {
BASELINE,
- WB,WACK,ITC1, // Write and callback(1) if ACK
- // handle decoders that dont ack a write
- VB,WACK,ITC1, // validate byte and callback(1) if correct
- FAIL // callback (-1)
+ WB,WACK,ITC1, // Write and callback(1) if ACK
+ // handle decoders that dont ack a write
+ VB,WACK,ITC1, // validate byte and callback(1) if correct
+ CALLFAIL // callback (-1)
};
const ackOp FLASH VERIFY_BYTE_PROG[] = {
@@ -379,10 +379,10 @@ const ackOp FLASH VERIFY_BYTE_PROG[] = {
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
- VB, WACK, ITCBV, // verify merged byte and return it if acked ok - with retry report
- FAIL };
-
-
+ VB, WACK, ITCB, // verify merged byte and return it if acked ok
+ CALLFAIL };
+
+
const ackOp FLASH READ_CV_PROG[] = {
BASELINE,
STARTMERGE, //clear bit and byte values ready for merge pass
@@ -402,8 +402,8 @@ const ackOp FLASH READ_CV_PROG[] = {
V0, WACK, MERGE,
V0, WACK, MERGE,
V0, WACK, MERGE,
- VB, WACK, ITCB, // verify merged byte and return it if acked ok
- FAIL }; // verification failed
+ VB, WACK, ITCB, // verify merged byte and return it if acked ok
+ CALLFAIL }; // verification failed
const ackOp FLASH LOCO_ID_PROG[] = {
@@ -469,8 +469,8 @@ const ackOp FLASH LOCO_ID_PROG[] = {
V0, WACK, MERGE,
V0, WACK, MERGE,
VB, WACK, ITCB, // verify merged byte and callback
- FAIL
- };
+ CALLFAIL
+ };
const ackOp FLASH SHORT_LOCO_ID_PROG[] = {
BASELINE,
@@ -486,8 +486,8 @@ const ackOp FLASH SHORT_LOCO_ID_PROG[] = {
SETBYTEL, // low byte of word
WB,WACK, // some decoders don't ACK writes
VB,WACK,ITCB,
- FAIL
-};
+ CALLFAIL
+};
const ackOp FLASH LONG_LOCO_ID_PROG[] = {
BASELINE,
@@ -510,8 +510,8 @@ const ackOp FLASH LONG_LOCO_ID_PROG[] = {
SETBYTEL, // low byte of word
WB,WACK,
VB,WACK,ITC1, // callback(1) means Ok
- FAIL
-};
+ CALLFAIL
+};
void DCC::writeCVByte(int16_t cv, byte byteValue, ACK_CALLBACK callback) {
ackManagerSetup(cv, byteValue, WRITE_BYTE_PROG, callback);
@@ -868,8 +868,8 @@ void DCC::ackManagerLoop() {
return;
}
break;
-
- case FAIL: // callback(-1)
+
+ case CALLFAIL: // callback(-1)
callback(-1);
return;
diff --git a/DCC.h b/DCC.h
index fbeb603..4c879c8 100644
--- a/DCC.h
+++ b/DCC.h
@@ -56,7 +56,7 @@ enum ackOp : byte
ITCBV, // If True callback(byte) - end of Verify Byte
ITCB7, // If True callback(byte &0x7F)
NAKFAIL, // if false callback(-1)
- FAIL, // callback(-1)
+ CALLFAIL, // callback(-1)
BIV, // Set ackManagerByte to initial value for Verify retry
STARTMERGE, // Clear bit and byte settings ready for merge pass
MERGE, // Merge previous wack response with byte value and decrement bit number (use for readimng CV bytes)
@@ -224,6 +224,8 @@ private:
#define ARDUINO_TYPE "TEENSY40"
#elif defined(ARDUINO_TEENSY41)
#define ARDUINO_TYPE "TEENSY41"
+#elif defined(ARDUINO_ARCH_ESP8266)
+#define ARDUINO_TYPE "ESP8266"
#else
#error CANNOT COMPILE - DCC++ EX ONLY WORKS WITH AN ARDUINO UNO, NANO 328, OR ARDUINO MEGA 1280/2560
#endif
diff --git a/DCCEX.h b/DCCEX.h
index 00d89de..a6a015a 100644
--- a/DCCEX.h
+++ b/DCCEX.h
@@ -33,6 +33,9 @@
#include "SerialManager.h"
#include "version.h"
#include "WifiInterface.h"
+#ifdef ESP_FAMILY
+#include "WifiESP.h"
+#endif
#if ETHERNET_ON == true
#include "EthernetInterface.h"
#endif
diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp
index f84c123..b16e837 100644
--- a/DCCEXParser.cpp
+++ b/DCCEXParser.cpp
@@ -23,6 +23,7 @@
* You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see .
*/
+#include "defines.h"
#include "StringFormatter.h"
#include "DCCEXParser.h"
#include "DCC.h"
@@ -37,7 +38,9 @@
#include "CommandDistributor.h"
#include "EEStore.h"
#include "DIAG.h"
+#ifndef ESP_FAMILY
#include
+#endif
////////////////////////////////////////////////////////////////////////////////
//
diff --git a/DCCTimer.cpp b/DCCTimer.cpp
index cd35293..3bcb5fd 100644
--- a/DCCTimer.cpp
+++ b/DCCTimer.cpp
@@ -49,7 +49,7 @@
#include "DCCTimer.h"
const int DCC_SIGNAL_TIME=58; // this is the 58uS DCC 1-bit waveform half-cycle
-const long CLOCK_CYCLES=(F_CPU / 1000000 * DCC_SIGNAL_TIME) >>1;
+const long CLOCK_CYCLES=(F_CPU / 1000000 * DCC_SIGNAL_TIME);
INTERRUPT_CALLBACK interruptHandler=0;
@@ -58,11 +58,11 @@ INTERRUPT_CALLBACK interruptHandler=0;
void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
interruptHandler=callback;
- noInterrupts();
+ noInterrupts();
ADC0.CTRLC = (ADC0.CTRLC & 0b00110000) | 0b01000011; // speed up analogRead sample time
TCB0.CTRLB = TCB_CNTMODE_INT_gc & ~TCB_CCMPEN_bm; // timer compare mode with output disabled
TCB0.CTRLA = TCB_CLKSEL_CLKDIV2_gc; // 8 MHz ~ 0.125 us
- TCB0.CCMP = CLOCK_CYCLES -1; // 1 tick less for timer reset
+ TCB0.CCMP = (CLOCK_CYCLES>>1) -1; // 1 tick less for timer reset
TCB0.INTFLAGS = TCB_CAPT_bm; // clear interrupt request flag
TCB0.INTCTRL = TCB_CAPT_bm; // Enable the interrupt
TCB0.CNT = 0;
@@ -151,6 +151,31 @@ void DCCTimer::read(uint8_t word, uint8_t *mac, uint8_t offset) {
}
#endif
+#elif defined(ARDUINO_ARCH_ESP8266)
+
+void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
+ interruptHandler=callback;
+ timer1_disable();
+
+ // There seem to be differnt ways to attach interrupt handler
+ // ETS_FRC_TIMER1_INTR_ATTACH(NULL, NULL);
+ // ETS_FRC_TIMER1_NMI_INTR_ATTACH(interruptHandler);
+ // Let us choose the one from the API
+ timer1_attachInterrupt(interruptHandler);
+
+ // not exactly sure of order:
+ timer1_enable(TIM_DIV1, TIM_EDGE, TIM_LOOP);
+ timer1_write(CLOCK_CYCLES);
+}
+// We do not support to use PWM to make the Waveform on ESP
+bool IRAM_ATTR DCCTimer::isPWMPin(byte pin) {
+ return false;
+}
+void IRAM_ATTR DCCTimer::setPWM(byte pin, bool high) {
+}
+
+
+
#else
// Arduino nano, uno, mega etc
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
@@ -164,10 +189,10 @@ void DCCTimer::read(uint8_t word, uint8_t *mac, uint8_t offset) {
void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
interruptHandler=callback;
- noInterrupts();
+ noInterrupts();
ADCSRA = (ADCSRA & 0b11111000) | 0b00000100; // speed up analogRead sample time
TCCR1A = 0;
- ICR1 = CLOCK_CYCLES;
+ ICR1 = CLOCK_CYCLES>>1;
TCNT1 = 0;
TCCR1B = _BV(WGM13) | _BV(CS10); // Mode 8, clock select 1
TIMSK1 = _BV(TOIE1); // Enable Software interrupt
diff --git a/DCCWaveform.cpp b/DCCWaveform.cpp
index 2c5ab9a..c135e36 100644
--- a/DCCWaveform.cpp
+++ b/DCCWaveform.cpp
@@ -24,6 +24,7 @@
#include
+#include "defines.h"
#include "DCCWaveform.h"
#include "DCCTimer.h"
#include "DIAG.h"
@@ -55,33 +56,48 @@ void DCCWaveform::begin(MotorDriver * mainDriver, MotorDriver * progDriver) {
DCCTimer::begin(DCCWaveform::interruptHandler);
}
-void DCCWaveform::loop(bool ackManagerActive) {
+#ifdef SLOW_ANALOG_READ
+// Flag to hold if we need to run ack checking in loop
+static bool ackflag = 0;
+#endif
+
+void IRAM_ATTR DCCWaveform::loop(bool ackManagerActive) {
mainTrack.checkPowerOverload(false);
progTrack.checkPowerOverload(ackManagerActive);
+#ifdef SLOW_ANALOG_READ
+ if (ackflag) {
+ progTrack.checkAck();
+ // reset flag AFTER check is done
+ ackflag = 0;
+ }
+#endif
}
#pragma GCC push_options
#pragma GCC optimize ("-O3")
-void DCCWaveform::interruptHandler() {
+void IRAM_ATTR DCCWaveform::interruptHandler() {
// call the timer edge sensitive actions for progtrack and maintrack
// member functions would be cleaner but have more overhead
byte sigMain=signalTransform[mainTrack.state];
byte sigProg=progTrackSyncMain? sigMain : signalTransform[progTrack.state];
-
// Set the signal state for both tracks
mainTrack.motorDriver->setSignal(sigMain);
progTrack.motorDriver->setSignal(sigProg);
-
// Move on in the state engine
mainTrack.state=stateTransform[mainTrack.state];
progTrack.state=stateTransform[progTrack.state];
-
-
// WAVE_PENDING means we dont yet know what the next bit is
- if (mainTrack.state==WAVE_PENDING) mainTrack.interrupt2();
- if (progTrack.state==WAVE_PENDING) progTrack.interrupt2();
- else if (progTrack.ackPending) progTrack.checkAck();
-
+ if (mainTrack.state==WAVE_PENDING)
+ mainTrack.interrupt2();
+ if (progTrack.state==WAVE_PENDING)
+ progTrack.interrupt2();
+#ifdef SLOW_ANALOG_READ
+ else if (progTrack.ackPending && ackflag == 0) // We need AND we are not already checking
+ ackflag = 1;
+#else
+ else if (progTrack.ackPending)
+ progTrack.checkAck();
+#endif
}
#pragma GCC push_options
@@ -206,7 +222,7 @@ const bool DCCWaveform::signalTransform[]={
#pragma GCC push_options
#pragma GCC optimize ("-O3")
-void DCCWaveform::interrupt2() {
+void IRAM_ATTR DCCWaveform::interrupt2() {
// calculate the next bit to be sent:
// set state WAVE_MID_1 for a 1=bit
// or WAVE_HIGH_0 for a 0 bit.
@@ -216,7 +232,9 @@ void DCCWaveform::interrupt2() {
remainingPreambles--;
// 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.
- updateMinimumFreeMemory(22);
+#ifndef ESP_FAMILY
+ updateMinimumFreeMemory(22);
+#endif
return;
}
@@ -317,14 +335,14 @@ byte DCCWaveform::getAck() {
#pragma GCC push_options
#pragma GCC optimize ("-O3")
-void DCCWaveform::checkAck() {
+void IRAM_ATTR DCCWaveform::checkAck() {
// This function operates in interrupt() time so must be fast and can't DIAG
if (sentResetsSincePacket > 6) { //ACK timeout
ackCheckDuration=millis()-ackCheckStart;
ackPending = false;
return;
}
-
+
int current=motorDriver->getCurrentRaw();
numAckSamples++;
if (current > ackMaxCurrent) ackMaxCurrent=current;
diff --git a/MotorDriver.cpp b/MotorDriver.cpp
index d65d2ea..2aa9639 100644
--- a/MotorDriver.cpp
+++ b/MotorDriver.cpp
@@ -25,11 +25,6 @@
#include "DCCTimer.h"
#include "DIAG.h"
-#define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH
-#define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW
-#define isHIGH(fastpin) (*fastpin.inout & fastpin.maskHIGH)
-#define isLOW(fastpin) (!isHIGH(fastpin))
-
bool MotorDriver::usePWM=false;
bool MotorDriver::commonFaultPin=false;
@@ -114,7 +109,7 @@ void MotorDriver::setBrake(bool on) {
else setLOW(fastBrakePin);
}
-void MotorDriver::setSignal( bool high) {
+void IRAM_ATTR MotorDriver::setSignal( bool high) {
if (usePWM) {
DCCTimer::setPWM(signalPin,high);
}
@@ -180,8 +175,8 @@ int MotorDriver::mA2raw( unsigned int mA) {
void MotorDriver::getFastPin(const FSH* type,int pin, bool input, FASTPIN & result) {
// DIAG(F("MotorDriver %S Pin=%d,"),type,pin);
- (void) type; // avoid compiler warning if diag not used above.
- uint8_t port = digitalPinToPort(pin);
+ (void) type; // avoid compiler warning if diag not used above.
+ PORTTYPE port = digitalPinToPort(pin);
if (input)
result.inout = portInputRegister(port);
else
diff --git a/MotorDriver.h b/MotorDriver.h
index 62d9cb5..1771c3a 100644
--- a/MotorDriver.h
+++ b/MotorDriver.h
@@ -29,13 +29,15 @@
#define UNUSED_PIN 127 // inside int8_t
#endif
-#if defined(__IMXRT1062__)
+#if defined(__IMXRT1062__) || defined (ARDUINO_ARCH_ESP8266)
+typedef uint32_t PORTTYPE;
struct FASTPIN {
volatile uint32_t *inout;
uint32_t maskHIGH;
uint32_t maskLOW;
};
#else
+typedef uint8_t PORTTYPE;
struct FASTPIN {
volatile uint8_t *inout;
uint8_t maskHIGH;
@@ -43,12 +45,30 @@ struct FASTPIN {
};
#endif
+#define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH
+#define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW
+#define isHIGH(fastpin) (*fastpin.inout & fastpin.maskHIGH)
+#define isLOW(fastpin) (!isHIGH(fastpin))
+
class MotorDriver {
public:
MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, int8_t brake_pin,
byte current_pin, float senseFactor, unsigned int tripMilliamps, byte faultPin);
virtual void setPower( bool on);
- virtual void setSignal( bool high);
+ void setSignal( bool high);/* {
+ if (usePWM) {
+ DCCTimer::setPWM(signalPin,high);
+ }
+
+ if (high) {
+ setHIGH(fastSignalPin);
+ if (dualSignal) setLOW(fastSignalPin2);
+ }
+ else {
+ setLOW(fastSignalPin);
+ if (dualSignal) setHIGH(fastSignalPin2);
+ }
+ };*/
virtual void setBrake( bool on);
virtual int getCurrentRaw();
virtual unsigned int raw2mA( int raw);
diff --git a/RingStream.cpp b/RingStream.cpp
index bf89e33..32beb0c 100644
--- a/RingStream.cpp
+++ b/RingStream.cpp
@@ -46,10 +46,11 @@ size_t RingStream::write(uint8_t b) {
return 1;
}
-int RingStream::read() {
- if ((_pos_read==_pos_write) && !_overflow) return -1; // empty
+int RingStream::read(byte advance) {
+ if ((_pos_read==_pos_write) && !_overflow) return -1; // empty
+ if (_pos_read == _mark) return -1;
byte b=_buffer[_pos_read];
- _pos_read++;
+ _pos_read += advance;
if (_pos_read==_len) _pos_read=0;
_overflow=false;
return b;
@@ -69,6 +70,7 @@ int RingStream::freeSpace() {
// mark start of message with client id (0...9)
void RingStream::mark(uint8_t b) {
+ //DIAG(F("Mark1 len=%d count=%d pr=%d pw=%d m=%d"),_len, _count,_pos_read,_pos_write,_mark);
_mark=_pos_write;
write(b); // client id
write((uint8_t)0); // count MSB placemarker
@@ -82,7 +84,12 @@ uint8_t RingStream::peekTargetMark() {
return _buffer[_mark];
}
+void RingStream::info() {
+ DIAG(F("Info len=%d count=%d pr=%d pw=%d m=%d"),_len, _count,_pos_read,_pos_write,_mark);
+}
+
bool RingStream::commit() {
+ //DIAG(F("Commit1 len=%d count=%d pr=%d pw=%d m=%d"),_len, _count,_pos_read,_pos_write,_mark);
if (_overflow) {
DIAG(F("RingStream(%d) commit(%d) OVERFLOW"),_len, _count);
// just throw it away
@@ -102,6 +109,8 @@ bool RingStream::commit() {
_mark++;
if (_mark==_len) _mark=0;
_buffer[_mark]=lowByte(_count);
+ _mark=_len+1;
+ //DIAG(F("Commit2 len=%d count=%d pr=%d pw=%d m=%d"),_len, _count,_pos_read,_pos_write,_mark);
return true; // commit worked
}
void RingStream::flush() {
diff --git a/RingStream.h b/RingStream.h
index 5821bc4..eb9f3a9 100644
--- a/RingStream.h
+++ b/RingStream.h
@@ -29,7 +29,8 @@ class RingStream : public Print {
virtual size_t write(uint8_t b);
using Print::write;
- int read();
+ inline int read() { return read(1); };
+ inline int peek() { return read(0); };
int count();
int freeSpace();
void mark(uint8_t b);
@@ -37,7 +38,10 @@ class RingStream : public Print {
uint8_t peekTargetMark();
void printBuffer(Print * streamer);
void flush();
+ void info();
+
private:
+ int read(byte advance);
int _len;
int _pos_write;
int _pos_read;
diff --git a/WifiESP.cpp b/WifiESP.cpp
new file mode 100644
index 0000000..f4e9773
--- /dev/null
+++ b/WifiESP.cpp
@@ -0,0 +1,264 @@
+/*
+ © 2021, Harald Barth.
+
+ 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 .
+*/
+
+#include "defines.h"
+#ifdef ESP_FAMILY
+#include
+#include
+#include
+#include
+
+#include "WifiESP.h"
+#include "DIAG.h"
+#include "RingStream.h"
+#include "CommandDistributor.h"
+#include
+
+static std::vector clients; // a list to hold all clients
+static AsyncServer *server;
+
+static RingStream *outboundRing = new RingStream(2048);
+
+static void handleError(void* arg, AsyncClient* client, int8_t error) {
+ DIAG(F("connection error %s from client %s"), client->errorToString(error), client->remoteIP().toString().c_str());
+}
+
+static void handleData(void* arg, AsyncClient* client, void *data, size_t len) {
+ //DIAG(F("data received from client %s"), client->remoteIP().toString().c_str());
+ uint8_t clientId;
+ for (clientId=0; clientIdmark(clientId);
+ CommandDistributor::parse(clientId,cmd,outboundRing);
+ outboundRing->commit();
+ }
+}
+
+//static AsyncClient *debugclient = NULL;
+
+bool sendData(AsyncClient *client, char* data, size_t count) {
+ size_t willsend = 0;
+
+ // reply to client
+ if (client->canSend()) {
+ while (count > 0) {
+ if (client->connected())
+ willsend = client->add(data, count); // add checks for space()
+ else
+ willsend = 0;
+ if (willsend < count) {
+ DIAG(F("Willsend %d of count %d"), willsend, count);
+ }
+ if (client->connected() && client->send()) {
+ count = count - willsend;
+ data = data + willsend;
+ } else {
+ DIAG(F("Could not send promised %d"), count);
+ return false;
+ }
+ }
+ // Did send all bytes we wanted
+ return true;
+ }
+ DIAG(F("Aborting: Busy or space=0"));
+ return false;
+}
+
+static void deleteClient(AsyncClient* client) {
+ uint8_t clientId;
+ for (clientId=0; clientIdremoteIP().toString().c_str());
+ deleteClient(client);
+}
+
+
+static void handleNewClient(void* arg, AsyncClient* client) {
+ DIAG(F("New client %s"), client->remoteIP().toString().c_str());
+
+ // add to list
+ clients.push_back(client);
+
+ // register events
+ client->onData(&handleData, NULL);
+ client->onError(&handleError, NULL);
+ client->onDisconnect(&handleDisconnect, NULL);
+ client->onTimeout(&handleTimeOut, NULL);
+
+}
+
+/* Things one _might_ want to do:
+ Disable soft watchdog: ESP.wdtDisable()
+ Enable soft watchdog: ESP.wdtEnable(X) ignores the value of X and enables it for fixed
+ time at least in version 3.0.2 of the esp8266 package.
+
+Internet says:
+
+I manage to complety disable the hardware watchdog on ESP8266 in order to run the benchmark CoreMark.
+
+void hw_wdt_disable(){
+ *((volatile uint32_t*) 0x60000900) &= ~(1); // Hardware WDT OFF
+}
+
+void hw_wdt_enable(){
+ *((volatile uint32_t*) 0x60000900) |= 1; // Hardware WDT ON
+}
+
+*/
+
+bool WifiESP::setup(const char *SSid,
+ const char *password,
+ const char *hostname,
+ int port,
+ const byte channel) {
+ bool havePassword = true;
+ bool haveSSID = true;
+ bool wifiUp = false;
+
+ // We are server and should not sleep
+ wifi_set_sleep_type(NONE_SLEEP_T);
+ // connects to access point
+
+ const char *yourNetwork = "Your network ";
+ if (strncmp(yourNetwork, SSid, 13) == 0 || strncmp("", SSid, 13) == 0)
+ haveSSID = false;
+ if (strncmp(yourNetwork, password, 13) == 0 || strncmp("", password, 13) == 0)
+ havePassword = false;
+
+ if (haveSSID && havePassword) {
+ WiFi.mode(WIFI_STA);
+ WiFi.setAutoReconnect(true);
+ WiFi.begin(SSid, password);
+ while (WiFi.status() != WL_CONNECTED) {
+ Serial.print('.');
+ delay(500);
+ }
+ if (WiFi.status() == WL_CONNECTED) {
+ DIAG(F("Wifi STA IP %s"),WiFi.localIP().toString().c_str());
+ wifiUp = true;
+ }
+ }
+ if (!haveSSID) {
+ // prepare all strings
+ String strSSID("DCC_");
+ String strPass("PASS_");
+ String strMac = WiFi.macAddress();
+ strMac.remove(0,9);
+ strMac.replace(":","");
+ strMac.replace(":","");
+ strSSID.concat(strMac);
+ strPass.concat(strMac);
+
+ WiFi.mode(WIFI_AP);
+ if (WiFi.softAP(strSSID.c_str(),
+ havePassword ? password : strPass.c_str(),
+ channel, false, 8)) {
+ DIAG(F("Wifi AP SSID %s PASS %s"),strSSID.c_str(),havePassword ? password : strPass.c_str());
+ DIAG(F("Wifi AP IP %s"),WiFi.softAPIP().toString().c_str());
+ wifiUp = true;
+ }
+ }
+
+
+ if (!wifiUp) {
+ DIAG(F("Wifi all fail"));
+ // no idea to go on
+ return false;
+ }
+
+ server = new AsyncServer(port); // start listening on tcp port
+
+ server->onClient(&handleNewClient, server);
+ server->begin();
+ DIAG(F("Server up port %d"),port);
+
+ return true;
+}
+
+void WifiESP::loop() {
+ AsyncClient *client = NULL;
+ // Do something with outboundRing
+ // call sendData
+ int clientId=outboundRing->peek();
+ if (clientId >= 0) {
+ if (clientId > clients.size()) {
+ // something is wrong with the ringbuffer position
+ outboundRing->info();
+ client = NULL;
+ } else {
+ client = clients[clientId];
+ }
+// if (client != debugclient) {
+// DIAG(F("new client pointer = %x from id %d"), client, clientId);
+// debugclient = client;
+// }
+ } else {
+ client = NULL;
+ }
+ if (clientId>=0 && client && client->connected() && client->canSend()) {
+ outboundRing->read();
+ int count=outboundRing->count();
+ //DIAG(F("Wifi reply client=%d, count=%d"), clientId,count);
+ {
+ char buffer[count+1];
+ for(int i=0;iread();
+ if (c >= 0)
+ buffer[i] = (char)c;
+ else {
+ DIAG(F("Ringread fail at %d"),i);
+ break;
+ }
+ }
+ buffer[count]=0;
+ //DIAG(F("SEND:%s COUNT:%d"),buffer,count);
+ uint8_t tries = 3;
+ while (! sendData(client, buffer, count)) {
+ DIAG(F("senData fail"));
+ yield();
+ if (tries == 0) break;
+ }
+ }
+ }
+#ifdef ESP_DEBUG
+ static unsigned long last = 0;
+ if (millis() - last > 60000) {
+ last = millis();
+ DIAG(F("+"));
+ }
+#endif
+ ESP.wdtFeed();
+}
+#endif //ESP_FAMILY
diff --git a/WifiESP.h b/WifiESP.h
new file mode 100644
index 0000000..47de4ed
--- /dev/null
+++ b/WifiESP.h
@@ -0,0 +1,37 @@
+/*
+ * © 2021, Harald Barth.
+ *
+ * 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 .
+ */
+
+#ifndef WifiESP_h
+#define WifiESP_h
+
+#include "FSH.h"
+
+class WifiESP
+{
+
+public:
+ static bool setup(const char *wifiESSID,
+ const char *wifiPassword,
+ const char *hostname,
+ const int port,
+ const byte channel);
+ static void loop();
+private:
+};
+#endif
diff --git a/config.example.h b/config.example.h
index 7dad23d..de88c29 100644
--- a/config.example.h
+++ b/config.example.h
@@ -44,7 +44,14 @@ The configuration file for DCC-EX Command Station
// |
// +-----------------------v
//
-#define MOTOR_SHIELD_TYPE STANDARD_MOTOR_SHIELD
+//#define MOTOR_SHIELD_TYPE STANDARD_MOTOR_SHIELD
+
+#define ESP_MOTOR_SHIELD F("ESP"), \
+ new MotorDriver(D3, D5, UNUSED_PIN, UNUSED_PIN, UNUSED_PIN, 2.99, 2000, UNUSED_PIN),\
+ new MotorDriver(D2, D6, UNUSED_PIN, UNUSED_PIN, A0 , 2.99, 2000, UNUSED_PIN)
+
+#define MOTOR_SHIELD_TYPE ESP_MOTOR_SHIELD
+
/////////////////////////////////////////////////////////////////////////////////////
//
// The IP port to talk to a WIFI or Ethernet shield.
@@ -56,7 +63,7 @@ The configuration file for DCC-EX Command Station
// NOTE: Only supported on Arduino Mega
// Set to false if you not even want it on the Arduino Mega
//
-#define ENABLE_WIFI true
+//#define ENABLE_WIFI true
/////////////////////////////////////////////////////////////////////////////////////
//
diff --git a/defines.h b/defines.h
index 67dbc96..aa98392 100644
--- a/defines.h
+++ b/defines.h
@@ -35,12 +35,20 @@
#endif
#endif
+////////////////////////////////////////////////////////////////////////////////
+//
+#if defined (ARDUINO_ARCH_ESP8266)
+#define ESP_FAMILY
+//#define ESP_DEBUG
+#define SLOW_ANALOG_READ
+#endif
+
////////////////////////////////////////////////////////////////////////////////
//
// WIFI_ON: All prereqs for running with WIFI are met
// Note: WIFI_CHANNEL may not exist in early config.h files so is added here if needed.
-#if (defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560) || defined(ARDUINO_SAMD_ZERO) || defined(TEENSYDUINO)) || defined(ARDUINO_AVR_NANO_EVERY)
+#if (defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560) || defined(ARDUINO_SAMD_ZERO) || defined(TEENSYDUINO)) || defined(ARDUINO_AVR_NANO_EVERY) || defined (ESP_FAMILY))
#define BIG_RAM
#endif
#if ENABLE_WIFI
@@ -53,8 +61,6 @@
#define WIFI_WARNING
#define WIFI_ON false
#endif
-#else
- #define WIFI_ON false
#endif
#if ENABLE_ETHERNET
diff --git a/freeMemory.cpp b/freeMemory.cpp
index df5ab8a..769d218 100644
--- a/freeMemory.cpp
+++ b/freeMemory.cpp
@@ -28,6 +28,8 @@ extern "C" char* sbrk(int);
#elif defined(__AVR__)
extern char *__brkval;
extern char *__malloc_heap_start;
+#elif defined(ARDUINO_ARCH_ESP8266)
+// supported but nothing needed here
#else
#error Unsupported board type
#endif
@@ -35,7 +37,7 @@ extern char *__malloc_heap_start;
static volatile int minimum_free_memory = __INT_MAX__;
-#if !defined(__IMXRT1062__)
+#if !defined(__IMXRT1062__) && !defined(ARDUINO_ARCH_ESP8266)
static inline int freeMemory() {
char top;
#if defined(__arm__)
@@ -56,7 +58,18 @@ int minimumFreeMemory() {
return retval;
}
+#elif defined(ARDUINO_ARCH_ESP8266)
+// ESP8266
+static inline int freeMemory() {
+ return ESP.getFreeHeap();
+}
+// Return low memory value.
+int minimumFreeMemory() {
+ int retval = minimum_free_memory;
+ return retval;
+}
#else
+// All types of TEENSYs
#if defined(ARDUINO_TEENSY40)
static const unsigned DTCM_START = 0x20000000UL;
static const unsigned OCRAM_START = 0x20200000UL;
@@ -109,4 +122,3 @@ void updateMinimumFreeMemory(unsigned char extraBytes) {
if (spare < 0) spare = 0;
if (spare < minimum_free_memory) minimum_free_memory = spare;
}
-