diff --git a/.github/workflows/sha.yml b/.github/workflows/sha.yml
new file mode 100644
index 0000000..a01e236
--- /dev/null
+++ b/.github/workflows/sha.yml
@@ -0,0 +1,33 @@
+name: SHA
+
+# Run this workflow ever time code is pushed to a branch
+# other than `main` in your repository
+on: push
+
+jobs:
+ # Set the job key. The key is displayed as the job name
+ # when a job name is not provided
+ sha:
+ # Name the Job
+ name: Commit SHA
+ # Set the type of machine to run on
+ runs-on: ubuntu-latest
+
+ steps:
+ # Checks out a copy of your repository on the ubuntu-latest machine
+ - name: Checkout code
+ uses: actions/checkout@v2
+
+ - name: Create SHA File
+ run: |
+ sha=$(git rev-parse --short "$GITHUB_SHA")
+ echo "#define GITHUB_SHA \"$sha\"" > GITHUB_SHA.h
+
+ - uses: EndBug/add-and-commit@v4 # You can change this to use a specific version
+ with:
+ add: 'GITHUB_SHA.h'
+ message: 'Committing a SHA'
+
+ env:
+ GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} # Leave this line unchanged
+
\ No newline at end of file
diff --git a/AnalogReadFast.h b/AnalogReadFast.h
deleted file mode 100644
index 445b233..0000000
--- a/AnalogReadFast.h
+++ /dev/null
@@ -1,46 +0,0 @@
-/*
- * AnalogReadFast.h
- *
- * Copyright (C) 2016 Albert van Dalen http://www.avdweb.nl
- *
- * This file is part of CommandStation.
- *
- * CommandStation 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.
- *
- * CommandStation 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 COMMANDSTATION_DCC_ANALOGREADFAST_H_
-#define COMMANDSTATION_DCC_ANALOGREADFAST_H_
-
-#include
-
-int inline analogReadFast(uint8_t ADCpin);
-#if defined(ARDUINO_ARCH_MEGAAVR)
-
-int inline analogReadFast(uint8_t ADCpin)
-{ byte ADC0CTRLCoriginal = ADC0.CTRLC;
- ADC0.CTRLC = (ADC0CTRLCoriginal & 0b00110000) + 0b01000011;
- int adc = analogRead(ADCpin);
- ADC0.CTRLC = ADC0CTRLCoriginal;
- return adc;
-}
-#else
-int inline analogReadFast(uint8_t ADCpin)
-{ byte ADCSRAoriginal = ADCSRA;
- ADCSRA = (ADCSRA & B11111000) | 4;
- int adc = analogRead(ADCpin);
- ADCSRA = ADCSRAoriginal;
- return adc;
-}
-#endif
-#endif // COMMANDSTATION_DCC_ANALOGREADFAST_H_
diff --git a/CommandStation-EX.ino b/CommandStation-EX.ino
index 4906498..1b08221 100644
--- a/CommandStation-EX.ino
+++ b/CommandStation-EX.ino
@@ -1,15 +1,49 @@
////////////////////////////////////////////////////////////////////////////////////
-// © 2020, Chris Harlow. All rights reserved.
+// DCC-EX CommandStation-EX Please see https://DCC-EX.com
//
-// This file is a demonstattion of setting up a DCC-EX
-// Command station with optional support for direct connection of WiThrottle devices
-// such as "Engine Driver". If you contriol your layout through JMRI
-// then DON'T connect throttles to this wifi, connect them to JMRI.
+// This file is the main sketch for the Command Station.
+//
+// CONFIGURATION:
+// Configuration is normally performed by editing a file called config.h.
+// This file is NOT shipped with the code so that if you pull a later version
+// of the code, your configuration will not be overwritten.
//
-// THE WIFI FEATURE IS NOT SUPPORTED ON ARDUINO DEVICES WITH ONLY 2KB RAM.
+// If you used the automatic installer program, config.h will have been created automatically.
+//
+// To obtain a starting copy of config.h please copy the file config.example.h which is
+// shipped with the code and may be updated as new features are added.
+//
+// If config.h is not found, config.example.h will be used with all defaults.
////////////////////////////////////////////////////////////////////////////////////
-#include "config.h"
+#if __has_include ( "config.h")
+ #include "config.h"
+#else
+ #warning config.h not found. Using defaults from config.example.h
+ #include "config.example.h"
+#endif
+
+
+/*
+ * © 2020,2021 Chris Harlow, Harald Barth, David Cutting,
+ * Fred Decker, Gregor Baues, Anthony W - Dayton All rights reserved.
+ *
+ *
+ * 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 "DCCEX.h"
// Create a serial command parser for the USB connection,
@@ -35,7 +69,7 @@ void setup()
// Start the WiFi interface on a MEGA, Uno cannot currently handle WiFi
#if WIFI_ON
- WifiInterface::setup(WIFI_SERIAL_LINK_SPEED, F(WIFI_SSID), F(WIFI_PASSWORD), F(WIFI_HOSTNAME), IP_PORT);
+ WifiInterface::setup(WIFI_SERIAL_LINK_SPEED, F(WIFI_SSID), F(WIFI_PASSWORD), F(WIFI_HOSTNAME), IP_PORT, WIFI_CHANNEL);
#endif // WIFI_ON
#if ETHERNET_ON
diff --git a/DCC.cpp b/DCC.cpp
index e75e073..840a4e2 100644
--- a/DCC.cpp
+++ b/DCC.cpp
@@ -481,9 +481,14 @@ void DCC::getLocoId(ACK_CALLBACK callback, bool blocking) {
}
void DCC::setLocoId(int id,ACK_CALLBACK callback, bool blocking) {
- if (id<=0 || id>9999) callback(-1);
- if (id<=127) ackManagerSetup(id,SHORT_LOCO_ID_PROG, callback, blocking);
- else ackManagerSetup(id | 0xc000,LONG_LOCO_ID_PROG, callback, blocking);
+ if (id<1 || id>10239) { //0x27FF according to standard
+ callback(-1);
+ return;
+ }
+ if (id<=127)
+ ackManagerSetup(id, SHORT_LOCO_ID_PROG, callback, blocking);
+ else
+ ackManagerSetup(id | 0xc000,LONG_LOCO_ID_PROG, callback, blocking);
}
void DCC::forgetLoco(int cab) { // removes any speed reminders for this loco
diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp
index a35803e..56f17a2 100644
--- a/DCCEXParser.cpp
+++ b/DCCEXParser.cpp
@@ -52,7 +52,7 @@ const int HASH_KEYWORD_ETHERNET = -30767;
const int HASH_KEYWORD_MAX = 16244;
const int HASH_KEYWORD_MIN = 15978;
-int DCCEXParser::stashP[MAX_PARAMS];
+int DCCEXParser::stashP[MAX_COMMAND_PARAMS];
bool DCCEXParser::stashBusy;
Print *DCCEXParser::stashStream = NULL;
@@ -102,7 +102,7 @@ void DCCEXParser::loop(Stream &stream)
Sensor::checkAll(&stream); // Update and print changes
}
-int DCCEXParser::splitValues(int result[MAX_PARAMS], const byte *cmd)
+int DCCEXParser::splitValues(int result[MAX_COMMAND_PARAMS], const byte *cmd)
{
byte state = 1;
byte parameterCount = 0;
@@ -111,10 +111,10 @@ int DCCEXParser::splitValues(int result[MAX_PARAMS], const byte *cmd)
bool signNegative = false;
// clear all parameters in case not enough found
- for (int i = 0; i < MAX_PARAMS; i++)
+ for (int i = 0; i < MAX_COMMAND_PARAMS; i++)
result[i] = 0;
- while (parameterCount < MAX_PARAMS)
+ while (parameterCount < MAX_COMMAND_PARAMS)
{
byte hot = *remainingCmd;
@@ -161,7 +161,7 @@ int DCCEXParser::splitValues(int result[MAX_PARAMS], const byte *cmd)
return parameterCount;
}
-int DCCEXParser::splitHexValues(int result[MAX_PARAMS], const byte *cmd)
+int DCCEXParser::splitHexValues(int result[MAX_COMMAND_PARAMS], const byte *cmd)
{
byte state = 1;
byte parameterCount = 0;
@@ -169,10 +169,10 @@ int DCCEXParser::splitHexValues(int result[MAX_PARAMS], const byte *cmd)
const byte *remainingCmd = cmd + 1; // skips the opcode
// clear all parameters in case not enough found
- for (int i = 0; i < MAX_PARAMS; i++)
+ for (int i = 0; i < MAX_COMMAND_PARAMS; i++)
result[i] = 0;
- while (parameterCount < MAX_PARAMS)
+ while (parameterCount < MAX_COMMAND_PARAMS)
{
byte hot = *remainingCmd;
@@ -251,7 +251,7 @@ void DCCEXParser::parse(Print *stream, byte *com, bool blocking)
(void)EEPROM; // tell compiler not to warn this is unused
if (Diag::CMD)
DIAG(F("\nPARSING:%s\n"), com);
- int p[MAX_PARAMS];
+ int p[MAX_COMMAND_PARAMS];
while (com[0] == '<' || com[0] == ' ')
com++; // strip off any number of < or spaces
byte params = splitValues(p, com);
@@ -770,13 +770,13 @@ bool DCCEXParser::parseD(Print *stream, int params, int p[])
}
// CALLBACKS must be static
-bool DCCEXParser::stashCallback(Print *stream, int p[MAX_PARAMS])
+bool DCCEXParser::stashCallback(Print *stream, int p[MAX_COMMAND_PARAMS])
{
if (stashBusy )
return false;
stashBusy = true;
stashStream = stream;
- memcpy(stashP, p, MAX_PARAMS * sizeof(p[0]));
+ memcpy(stashP, p, MAX_COMMAND_PARAMS * sizeof(p[0]));
return true;
}
void DCCEXParser::callback_W(int result)
diff --git a/DCCEXParser.h b/DCCEXParser.h
index f0546b2..c1dfd13 100644
--- a/DCCEXParser.h
+++ b/DCCEXParser.h
@@ -34,7 +34,7 @@ struct DCCEXParser
static void setFilter(FILTER_CALLBACK filter);
static void setRMFTFilter(FILTER_CALLBACK filter);
static void setAtCommandCallback(AT_COMMAND_CALLBACK filter);
- static const int MAX_PARAMS=10; // Must not exceed this
+ static const int MAX_COMMAND_PARAMS=10; // Must not exceed this
private:
@@ -42,8 +42,8 @@ struct DCCEXParser
byte bufferLength=0;
bool inCommandPayload=false;
byte buffer[MAX_BUFFER+2];
- int splitValues( int result[MAX_PARAMS], const byte * command);
- int splitHexValues( int result[MAX_PARAMS], const byte * command);
+ int splitValues( int result[MAX_COMMAND_PARAMS], const byte * command);
+ int splitHexValues( int result[MAX_COMMAND_PARAMS], const byte * command);
bool parseT(Print * stream, int params, int p[]);
bool parseZ(Print * stream, int params, int p[]);
@@ -55,8 +55,8 @@ struct DCCEXParser
static bool stashBusy;
static Print * stashStream;
- static int stashP[MAX_PARAMS];
- bool stashCallback(Print * stream, int p[MAX_PARAMS]);
+ static int stashP[MAX_COMMAND_PARAMS];
+ bool stashCallback(Print * stream, int p[MAX_COMMAND_PARAMS]);
static void callback_W(int result);
static void callback_B(int result);
static void callback_R(int result);
diff --git a/DCCTimer.cpp b/DCCTimer.cpp
index bbec1c1..46cd2ea 100644
--- a/DCCTimer.cpp
+++ b/DCCTimer.cpp
@@ -25,6 +25,21 @@
* DCCEX works on a single timer interrupt at a regular 58uS interval.
* The DCCWaveform class generates the signals to the motor shield
* based on this timer.
+ *
+ * If the motor drivers are BOTH configured to use the correct 2 pins for the architecture,
+ * (see isPWMPin() function. )
+ * then this allows us to use a hardware driven pin switching arrangement which is
+ * achieved by setting the duty cycle of the NEXT clock interrupt to 0% or 100% depending on
+ * the required pin state. (see setPWM())
+ * This is more accurate than the software interrupt but at the expense of
+ * limiting the choice of available pins.
+ * Fortunately, a standard motor shield on a Mega uses pins that qualify for PWM...
+ * Other shields may be jumpered to PWM pins or run directly using the software interrupt.
+ *
+ * Because the PWM-based waveform is effectively set half a cycle after the software version,
+ * it is not acceptable to drive the two tracks on different methiods or it would cause
+ * problems for <1 JOIN> etc.
+ *
*/
#include "DCCTimer.h"
@@ -35,12 +50,14 @@ INTERRUPT_CALLBACK interruptHandler=0;
#ifdef ARDUINO_ARCH_MEGAAVR
// Arduino unoWifi Rev2 and nanoEvery architectire
+
void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
interruptHandler=callback;
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 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;
@@ -53,12 +70,34 @@ INTERRUPT_CALLBACK interruptHandler=0;
TCB0.INTFLAGS = TCB_CAPT_bm;
interruptHandler();
}
-
+
+ bool DCCTimer::isPWMPin(byte pin) {
+ return false; // TODO what are the relevant pins?
+ }
+
+ void DCCTimer::setPWM(byte pin, bool high) {
+ // TODO what are the relevant pins?
+ }
+
+ void DCCTimer::getSimulatedMacAddress(byte mac[6]) {
+ memcpy(mac,(void *) &SIGROW.SERNUM0,6); // serial number
+ }
+
#else
- // Arduino nano, uno, mega etc
+ // Arduino nano, uno, mega etc
+#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+ #define TIMER1_A_PIN 11
+ #define TIMER1_B_PIN 12
+ #define TIMER1_C_PIN 13
+#else
+ #define TIMER1_A_PIN 9
+ #define TIMER1_B_PIN 10
+#endif
+
void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
interruptHandler=callback;
- noInterrupts();
+ noInterrupts();
+ ADCSRA = (ADCSRA & 0b11111000) | 0b00000100; // speed up analogRead sample time
TCCR1A = 0;
ICR1 = CLOCK_CYCLES;
TCNT1 = 0;
@@ -69,4 +108,38 @@ INTERRUPT_CALLBACK interruptHandler=0;
// ISR called by timer interrupt every 58uS
ISR(TIMER1_OVF_vect){ interruptHandler(); }
+
+// Alternative pin manipulation via PWM control.
+ bool DCCTimer::isPWMPin(byte pin) {
+ return pin==TIMER1_A_PIN
+ || pin==TIMER1_B_PIN
+ #ifdef TIMER1_C_PIN
+ || pin==TIMER1_C_PIN
+ #endif
+ ;
+ }
+
+ void DCCTimer::setPWM(byte pin, bool high) {
+ if (pin==TIMER1_A_PIN) {
+ TCCR1A |= _BV(COM1A1);
+ OCR1A= high?1024:0;
+ }
+ else if (pin==TIMER1_B_PIN) {
+ TCCR1A |= _BV(COM1B1);
+ OCR1B= high?1024:0;
+ }
+ #ifdef TIMER1_C_PIN
+ else if (pin==TIMER1_C_PIN) {
+ TCCR1A |= _BV(COM1C1);
+ OCR1C= high?1024:0;
+ }
+ #endif
+ }
+
+
+ #include
+ void DCCTimer::getSimulatedMacAddress(byte mac[6]) {
+ for (byte i=0; i<6; i++) mac[i]=boot_signature_byte_get(0x0E + i);
+ }
+
#endif
diff --git a/DCCTimer.h b/DCCTimer.h
index a388349..dfe9ef2 100644
--- a/DCCTimer.h
+++ b/DCCTimer.h
@@ -7,6 +7,9 @@ typedef void (*INTERRUPT_CALLBACK)();
class DCCTimer {
public:
static void begin(INTERRUPT_CALLBACK interrupt);
+ static void getSimulatedMacAddress(byte mac[6]);
+ static bool isPWMPin(byte pin);
+ static void setPWM(byte pin, bool high);
private:
};
diff --git a/DCCWaveform.cpp b/DCCWaveform.cpp
index 8344995..439717e 100644
--- a/DCCWaveform.cpp
+++ b/DCCWaveform.cpp
@@ -17,6 +17,7 @@
* You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see .
*/
+ #pragma GCC optimize ("-O3")
#include
#include "DCCWaveform.h"
@@ -38,6 +39,9 @@ void DCCWaveform::begin(MotorDriver * mainDriver, MotorDriver * progDriver) {
progTripValue = progDriver->mA2raw(TRIP_CURRENT_PROG); // need only calculate once hence static
mainTrack.setPowerMode(POWERMODE::OFF);
progTrack.setPowerMode(POWERMODE::OFF);
+ MotorDriver::usePWM= mainDriver->isPWMCapable() && progDriver->isPWMCapable();
+ if (MotorDriver::usePWM) DIAG(F("\nWaveform using PWM pins for accuracy."));
+ else DIAG(F("\nWaveform accuracy limited by signal pin configuration."));
DCCTimer::begin(DCCWaveform::interruptHandler);
}
@@ -119,6 +123,11 @@ void DCCWaveform::checkPowerOverload() {
case POWERMODE::ON:
// Check current
lastCurrent=motorDriver->getCurrentRaw();
+ if (lastCurrent < 0) {
+ // We have a fault pin condition to take care of
+ DIAG(F("\n*** %S FAULT PIN ACTIVE TOGGLE POWER ON THIS OR BOTH TRACKS ***\n"), isMainTrack ? F("MAIN") : F("PROG"));
+ lastCurrent = -lastCurrent;
+ }
if (lastCurrent <= tripValue) {
sampleDelay = POWER_SAMPLE_ON_WAIT;
if(power_good_counter<100)
@@ -129,9 +138,9 @@ void DCCWaveform::checkPowerOverload() {
setPowerMode(POWERMODE::OVERLOAD);
unsigned int mA=motorDriver->raw2mA(lastCurrent);
unsigned int maxmA=motorDriver->raw2mA(tripValue);
- DIAG(F("\n*** %S TRACK POWER OVERLOAD current=%d max=%d offtime=%l ***\n"), isMainTrack ? F("MAIN") : F("PROG"), mA, maxmA, power_sample_overload_wait);
power_good_counter=0;
sampleDelay = power_sample_overload_wait;
+ DIAG(F("\n*** %S TRACK POWER OVERLOAD current=%d max=%d offtime=%d ***\n"), isMainTrack ? F("MAIN") : F("PROG"), mA, maxmA, sampleDelay);
if (power_sample_overload_wait >= 10000)
power_sample_overload_wait = 10000;
else
@@ -142,6 +151,8 @@ void DCCWaveform::checkPowerOverload() {
// Try setting it back on after the OVERLOAD_WAIT
setPowerMode(POWERMODE::ON);
sampleDelay = POWER_SAMPLE_ON_WAIT;
+ // Debug code....
+ DIAG(F("\n*** %S TRACK POWER RESET delay=%d ***\n"), isMainTrack ? F("MAIN") : F("PROG"), sampleDelay);
break;
default:
sampleDelay = 999; // cant get here..meaningless statement to avoid compiler warning.
@@ -198,7 +209,10 @@ void DCCWaveform::interrupt2() {
}
else if (packetPending) {
// Copy pending packet to transmit packet
- for (int b = 0; b < pendingLength; b++) transmitPacket[b] = pendingPacket[b];
+ // a fixed length memcpy is faster than a variable length loop for these small lengths
+ // for (int b = 0; b < pendingLength; b++) transmitPacket[b] = pendingPacket[b];
+ memcpy( transmitPacket, pendingPacket, sizeof(pendingPacket));
+
transmitLength = pendingLength;
transmitRepeats = pendingRepeats;
packetPending = false;
@@ -223,7 +237,7 @@ void DCCWaveform::schedulePacket(const byte buffer[], byte byteCount, byte repea
while (packetPending);
byte checksum = 0;
- for (int b = 0; b < byteCount; b++) {
+ for (byte b = 0; b < byteCount; b++) {
checksum ^= buffer[b];
pendingPacket[b] = buffer[b];
}
diff --git a/DCCWaveform.h b/DCCWaveform.h
index 8f82678..890ba49 100644
--- a/DCCWaveform.h
+++ b/DCCWaveform.h
@@ -29,7 +29,7 @@ const int POWER_SAMPLE_OVERLOAD_WAIT = 20;
// Number of preamble bits.
const int PREAMBLE_BITS_MAIN = 16;
const int PREAMBLE_BITS_PROG = 22;
-const byte MAX_PACKET_SIZE = 12;
+const byte MAX_PACKET_SIZE = 5; // NMRA standard exrtended packets
// The WAVE_STATE enum is deliberately numbered because a change of order would be catastrophic
// to the transform array.
diff --git a/EthernetInterface.cpp b/EthernetInterface.cpp
index ebc21c4..38a0b24 100644
--- a/EthernetInterface.cpp
+++ b/EthernetInterface.cpp
@@ -17,13 +17,18 @@
* along with CommandStation. If not, see .
*
*/
-
-#include "config.h"
-#include "defines.h" // This should be changed to DCCEX.h when possible
+#if __has_include ( "config.h")
+ #include "config.h"
+#else
+ #warning config.h not found. Using defaults from config.example.h
+ #include "config.example.h"
+#endif
+#include "defines.h"
#if ETHERNET_ON == true
#include "EthernetInterface.h"
#include "DIAG.h"
#include "CommandDistributor.h"
+#include "DCCTimer.h"
EthernetInterface * EthernetInterface::singleton=NULL;
/**
@@ -45,10 +50,15 @@ void EthernetInterface::setup()
*/
EthernetInterface::EthernetInterface()
{
- byte mac[]=MAC_ADDRESS;
+ byte mac[6];
+ DCCTimer::getSimulatedMacAddress(mac);
+ DIAG(F("\n+++++ Ethernet Setup. Simulatd mac="));
+ for (byte i=0;ibegin();
LCD(4,F("IP: %d.%d.%d.%d"), ip[0], ip[1], ip[2], ip[3]);
- LCD(5,F("Port:%d"), LISTEN_PORT);
+ LCD(5,F("Port:%d"), IP_PORT);
outboundRing=new RingStream(OUTBOUND_RING_SIZE);
}
diff --git a/EthernetInterface.h b/EthernetInterface.h
index 23cc6cd..87bb8b6 100644
--- a/EthernetInterface.h
+++ b/EthernetInterface.h
@@ -22,7 +22,12 @@
#ifndef EthernetInterface_h
#define EthernetInterface_h
-
+#if __has_include ( "config.h")
+ #include "config.h"
+#else
+ #warning config.h not found. Using defaults from config.example.h
+ #include "config.example.h"
+#endif
#include "DCCEXParser.h"
#include
#include
@@ -33,11 +38,7 @@
* @brief Network Configuration
*
*/
-#ifndef MAC_ADDRESS
-#error define MAC_ADDRESS in config.h
-#endif
-#define LISTEN_PORT 2560 // default listen port for the server
#define MAX_ETH_BUFFER 512
#define OUTBOUND_RING_SIZE 2048
diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h
index cca6c46..a22d209 100644
--- a/GITHUB_SHA.h
+++ b/GITHUB_SHA.h
@@ -1 +1 @@
-#define GITHUB_SHA "9db6d36"
+#define GITHUB_SHA "0228345"
diff --git a/LCD_Implementation.h b/LCD_Implementation.h
index 45e0429..cb88a8b 100644
--- a/LCD_Implementation.h
+++ b/LCD_Implementation.h
@@ -27,7 +27,6 @@
#ifndef LCD_Implementation_h
#define LCD_Implementation_h
-#include "config.h"
#include
#include "LCDDisplay.h"
diff --git a/MotorDriver.cpp b/MotorDriver.cpp
index c4ef893..6cc1d10 100644
--- a/MotorDriver.cpp
+++ b/MotorDriver.cpp
@@ -18,51 +18,72 @@
*/
#include
#include "MotorDriver.h"
-#include "AnalogReadFast.h"
+#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))
-
-#if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_SAMC) || defined(ARDUINO_ARCH_MEGAAVR)
- #define WritePin digitalWrite
- #define ReadPin digitalRead
-#else
- // use the DIO2 libraray for much faster pin access
- #define GPIO2_PREFER_SPEED 1
- #include // use IDE menu Tools..Manage Libraries to locate and install DIO2
- #define WritePin digitalWrite2
- #define ReadPin digitalRead2
-#endif
-
+bool MotorDriver::usePWM=false;
+
MotorDriver::MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, int8_t brake_pin,
byte current_pin, float sense_factor, unsigned int trip_milliamps, byte fault_pin) {
powerPin=power_pin;
+ getFastPin(F("POWER"),powerPin,fastPowerPin);
+ pinMode(powerPin, OUTPUT);
+
signalPin=signal_pin;
+ getFastPin(F("SIG"),signalPin,fastSignalPin);
+ pinMode(signalPin, OUTPUT);
+
signalPin2=signal_pin2;
+ if (signalPin2!=UNUSED_PIN) {
+ dualSignal=true;
+ getFastPin(F("SIG2"),signalPin2,fastSignalPin2);
+ pinMode(signalPin2, OUTPUT);
+ }
+ else dualSignal=false;
+
brakePin=brake_pin;
+ if (brake_pin!=UNUSED_PIN){
+ invertBrake=brake_pin < 0;
+ brakePin=invertBrake ? 0-brake_pin : brake_pin;
+ getFastPin(F("BRAKE"),brakePin,fastBrakePin);
+ pinMode(brakePin, OUTPUT);
+ setBrake(false);
+ }
+ else brakePin=UNUSED_PIN;
+
currentPin=current_pin;
- senseFactor=sense_factor;
+ pinMode(currentPin, INPUT);
+
faultPin=fault_pin;
+ if (faultPin != UNUSED_PIN) {
+ getFastPin(F("FAULT"),faultPin, 1 /*input*/, fastFaultPin);
+ pinMode(faultPin, INPUT);
+ }
+
+ senseFactor=sense_factor;
tripMilliamps=trip_milliamps;
rawCurrentTripValue=(int)(trip_milliamps / sense_factor);
- simulatedOverload=(int)(32000/senseFactor);
- pinMode(powerPin, OUTPUT);
- pinMode(brakePin < 0 ? -brakePin : brakePin, OUTPUT);
- setBrake(false);
- pinMode(signalPin, OUTPUT);
- if (signalPin2 != UNUSED_PIN) pinMode(signalPin2, OUTPUT);
- pinMode(currentPin, INPUT);
- if (faultPin != UNUSED_PIN) pinMode(faultPin, INPUT);
}
+bool MotorDriver::isPWMCapable() {
+ return (!dualSignal) && DCCTimer::isPWMPin(signalPin);
+}
+
+
void MotorDriver::setPower(bool on) {
- if (brakePin == -4 && on) {
+ if (on) {
// toggle brake before turning power on - resets overcurrent error
// on the Pololu board if brake is wired to ^D2.
setBrake(true);
setBrake(false);
+ setHIGH(fastPowerPin);
}
- WritePin(powerPin, on ? HIGH : LOW);
+ else setLOW(fastPowerPin);
}
// setBrake applies brake if on == true. So to get
@@ -74,30 +95,35 @@ void MotorDriver::setPower(bool on) {
// compensate for that.
//
void MotorDriver::setBrake(bool on) {
- bool state = on;
- byte pin = brakePin;
- if (brakePin < 0) {
- pin=-pin;
- state=!state;
- }
- WritePin(pin, state ? HIGH : LOW);
- //DIAG(F("BrakePin: %d is %d\n"), pin, ReadPin(pin));
+ if (brakePin == UNUSED_PIN) return;
+ if (on ^ invertBrake) setHIGH(fastBrakePin);
+ else setLOW(fastBrakePin);
}
void MotorDriver::setSignal( bool high) {
- WritePin(signalPin, high ? HIGH : LOW);
- if (signalPin2 != UNUSED_PIN) WritePin(signalPin2, high ? LOW : HIGH);
+ if (usePWM) {
+ DCCTimer::setPWM(signalPin,high);
+ }
+ else {
+ if (high) {
+ setHIGH(fastSignalPin);
+ if (dualSignal) setLOW(fastSignalPin2);
+ }
+ else {
+ setLOW(fastSignalPin);
+ if (dualSignal) setHIGH(fastSignalPin2);
+ }
+ }
}
-
int MotorDriver::getCurrentRaw() {
- if (faultPin != UNUSED_PIN && ReadPin(faultPin) == LOW && ReadPin(powerPin) == HIGH)
- return simulatedOverload;
-
+ int current = analogRead(currentPin);
+ if (faultPin != UNUSED_PIN && isLOW(fastFaultPin) && isHIGH(fastPowerPin))
+ return -current;
+ return current;
// IMPORTANT: This function can be called in Interrupt() time within the 56uS timer
// The default analogRead takes ~100uS which is catastrphic
- // so analogReadFast is used here. (-2uS)
- return analogReadFast(currentPin);
+ // so DCCTimer has set the sample time to be much faster.
}
unsigned int MotorDriver::raw2mA( int raw) {
@@ -106,3 +132,15 @@ unsigned int MotorDriver::raw2mA( int raw) {
int MotorDriver::mA2raw( unsigned int mA) {
return (int)(mA / senseFactor);
}
+
+void MotorDriver::getFastPin(const FSH* type,int pin, bool input, FASTPIN & result) {
+ DIAG(F("\nMotorDriver %S Pin=%d,"),type,pin);
+ uint8_t port = digitalPinToPort(pin);
+ if (input)
+ result.inout = portInputRegister(port);
+ else
+ result.inout = portOutputRegister(port);
+ result.maskHIGH = digitalPinToBitMask(pin);
+ result.maskLOW = ~result.maskHIGH;
+ DIAG(F(" port=0x%x, inoutpin=0x%x, isinput=%d, mask=0x%x\n"),port, result.inout,input,result.maskHIGH);
+}
diff --git a/MotorDriver.h b/MotorDriver.h
index 077ab1d..2c6b230 100644
--- a/MotorDriver.h
+++ b/MotorDriver.h
@@ -18,12 +18,20 @@
*/
#ifndef MotorDriver_h
#define MotorDriver_h
+#include "FSH.h"
+
// Virtualised Motor shield 1-track hardware Interface
#ifndef UNUSED_PIN // sync define with the one in MotorDrivers.h
#define UNUSED_PIN 127 // inside int8_t
#endif
+struct FASTPIN {
+ volatile uint8_t *inout;
+ uint8_t maskHIGH;
+ uint8_t maskLOW;
+};
+
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);
@@ -34,15 +42,22 @@ class MotorDriver {
virtual unsigned int raw2mA( int raw);
virtual int mA2raw( unsigned int mA);
inline int getRawCurrentTripValue() {
- return rawCurrentTripValue;
+ return rawCurrentTripValue;
}
-
+ bool isPWMCapable();
+ static bool usePWM;
+
private:
- byte powerPin, signalPin, signalPin2, currentPin, faultPin;
- int8_t brakePin; // negative means pin is inverted
+ void getFastPin(const FSH* type,int pin, bool input, FASTPIN & result);
+ void getFastPin(const FSH* type,int pin, FASTPIN & result) {
+ getFastPin(type, pin, 0, result);
+ }
+ byte powerPin, signalPin, signalPin2, currentPin, faultPin, brakePin;
+ FASTPIN fastPowerPin,fastSignalPin, fastSignalPin2, fastBrakePin,fastFaultPin;
+ bool dualSignal; // true to use signalPin2
+ bool invertBrake; // brake pin passed as negative means pin is inverted
float senseFactor;
unsigned int tripMilliamps;
int rawCurrentTripValue;
- int simulatedOverload;
};
#endif
diff --git a/WifiInboundHandler.cpp b/WifiInboundHandler.cpp
index 2463921..02d3e0a 100644
--- a/WifiInboundHandler.cpp
+++ b/WifiInboundHandler.cpp
@@ -1,3 +1,23 @@
+/*
+ * © 2020, Chris Harlow. All rights reserved.
+ * © 2020, Harald Barth.
+ *
+ * This file is part of Asbelos DCC 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 .
+ */
+#ifndef ARDUINO_AVR_UNO_WIFI_REV2
#include
#include "WifiInboundHandler.h"
#include "RingStream.h"
@@ -228,3 +248,5 @@ void WifiInboundHandler::purgeCurrentCIPSEND() {
pendingCipsend=false;
clientPendingCIPSEND=-1;
}
+
+#endif
diff --git a/WifiInterface.cpp b/WifiInterface.cpp
index eb96885..5d04400 100644
--- a/WifiInterface.cpp
+++ b/WifiInterface.cpp
@@ -17,7 +17,8 @@
You should have received a copy of the GNU General Public License
along with CommandStation. If not, see .
*/
-
+#ifndef ARDUINO_AVR_UNO_WIFI_REV2
+// This code is NOT compiled on a unoWifiRev2 processor which uses a different architecture
#include "WifiInterface.h" /* config.h included there */
#include
#include "DIAG.h"
@@ -25,11 +26,9 @@
#include "WifiInboundHandler.h"
-const char FLASH READY_SEARCH[] = "\r\nready\r\n";
-const char FLASH OK_SEARCH[] = "\r\nOK\r\n";
-const char FLASH END_DETAIL_SEARCH[] = "@ 1000";
-const char FLASH SEND_OK_SEARCH[] = "\r\nSEND OK\r\n";
-const char FLASH IPD_SEARCH[] = "+IPD";
+
+
+
const unsigned long LOOP_TIMEOUT = 2000;
bool WifiInterface::connected = false;
Stream * WifiInterface::wifiStream;
@@ -43,7 +42,7 @@ Stream * WifiInterface::wifiStream;
//
// Figure out number of serial ports depending on hardware
//
-#if defined(ARDUINO_AVR_UNO)
+#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_NANO)
#define NUM_SERIAL 0
#endif
@@ -59,7 +58,8 @@ bool WifiInterface::setup(long serial_link_speed,
const FSH *wifiESSID,
const FSH *wifiPassword,
const FSH *hostname,
- const int port) {
+ const int port,
+ const byte channel) {
wifiSerialState wifiUp = WIFI_NOAT;
@@ -74,7 +74,7 @@ bool WifiInterface::setup(long serial_link_speed,
#if NUM_SERIAL > 0
Serial1.begin(serial_link_speed);
- wifiUp = setup(Serial1, wifiESSID, wifiPassword, hostname, port);
+ wifiUp = setup(Serial1, wifiESSID, wifiPassword, hostname, port, channel);
#endif
// Other serials are tried, depending on hardware.
@@ -82,7 +82,7 @@ bool WifiInterface::setup(long serial_link_speed,
if (wifiUp == WIFI_NOAT)
{
Serial2.begin(serial_link_speed);
- wifiUp = setup(Serial2, wifiESSID, wifiPassword, hostname, port);
+ wifiUp = setup(Serial2, wifiESSID, wifiPassword, hostname, port, channel);
}
#endif
@@ -90,7 +90,7 @@ bool WifiInterface::setup(long serial_link_speed,
if (wifiUp == WIFI_NOAT)
{
Serial3.begin(serial_link_speed);
- wifiUp = setup(Serial3, wifiESSID, wifiPassword, hostname, port);
+ wifiUp = setup(Serial3, wifiESSID, wifiPassword, hostname, port, channel);
}
#endif
@@ -108,7 +108,7 @@ bool WifiInterface::setup(long serial_link_speed,
}
wifiSerialState WifiInterface::setup(Stream & setupStream, const FSH* SSid, const FSH* password,
- const FSH* hostname, int port) {
+ const FSH* hostname, int port, byte channel) {
wifiSerialState wifiState;
static uint8_t ntry = 0;
ntry++;
@@ -117,7 +117,7 @@ wifiSerialState WifiInterface::setup(Stream & setupStream, const FSH* SSid, con
DIAG(F("\n++ Wifi Setup Try %d ++\n"), ntry);
- wifiState = setup2( SSid, password, hostname, port);
+ wifiState = setup2( SSid, password, hostname, port, channel);
if (wifiState == WIFI_NOAT) {
DIAG(F("\n++ Wifi Setup NO AT ++\n"));
@@ -126,7 +126,7 @@ wifiSerialState WifiInterface::setup(Stream & setupStream, const FSH* SSid, con
if (wifiState == WIFI_CONNECTED) {
StringFormatter::send(wifiStream, F("ATE0\r\n")); // turn off the echo
- checkForOK(200, OK_SEARCH, true);
+ checkForOK(200, true);
}
@@ -140,145 +140,170 @@ wifiSerialState WifiInterface::setup(Stream & setupStream, const FSH* SSid, con
#pragma GCC diagnostic ignored "-Wunused-parameter"
#endif
wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password,
- const FSH* hostname, int port) {
+ const FSH* hostname, int port, byte channel) {
bool ipOK = false;
bool oldCmd = false;
char macAddress[17]; // mac address extraction
-
+
// First check... Restarting the Arduino does not restart the ES.
// There may alrerady be a connection with data in the pipeline.
// If there is, just shortcut the setup and continue to read the data as normal.
- if (checkForOK(200,IPD_SEARCH, true)) {
+ if (checkForOK(200,F("+IPD"), true)) {
DIAG(F("\nPreconfigured Wifi already running with data waiting\n"));
- // loopstate=4; // carry on from correct place... or not as the case may be
return WIFI_CONNECTED;
}
StringFormatter::send(wifiStream, F("AT\r\n")); // Is something here that understands AT?
- if(!checkForOK(200, OK_SEARCH, true))
+ if(!checkForOK(200, true))
return WIFI_NOAT; // No AT compatible WiFi module here
StringFormatter::send(wifiStream, F("ATE1\r\n")); // Turn on the echo, se we can see what's happening
- checkForOK(2000, OK_SEARCH, true); // Makes this visible on the console
+ checkForOK(2000, true); // Makes this visible on the console
// Display the AT version information
StringFormatter::send(wifiStream, F("AT+GMR\r\n"));
- checkForOK(2000, OK_SEARCH, true, false); // Makes this visible on the console
+ checkForOK(2000, true, false); // Makes this visible on the console
#ifdef DONT_TOUCH_WIFI_CONF
DIAG(F("\nDONT_TOUCH_WIFI_CONF was set: Using existing config\n"));
#else
StringFormatter::send(wifiStream, F("AT+CWMODE=1\r\n")); // configure as "station" = WiFi client
- checkForOK(1000, OK_SEARCH, true); // Not always OK, sometimes "no change"
+ checkForOK(1000, true); // Not always OK, sometimes "no change"
+
+ // Older ES versions have AT+CWJAP, newer ones have AT+CWJAP_CUR and AT+CWHOSTNAME
+ StringFormatter::send(wifiStream, F("AT+CWJAP?\r\n"));
+ if (checkForOK(2000, true)) {
+ oldCmd=true;
+ while (wifiStream->available()) StringFormatter::printEscape( wifiStream->read()); /// THIS IS A DIAG IN DISGUISE
+ }
- // If the source code looks unconfigured, check if the
- // ESP8266 is preconfigured. We check the first 13 chars
- // of the SSid.
const char *yourNetwork = "Your network ";
- if (strncmp_P(yourNetwork, (const char*)SSid, 13) == 0 || ((const char *)SSid)[0] == '\0') {
- delay(8000); // give a preconfigured ES8266 a chance to connect to a router
- // typical connect time approx 7 seconds
- StringFormatter::send(wifiStream, F("AT+CIFSR\r\n"));
- if (checkForOK(5000, (const char*) F("+CIFSR:STAIP"), true,false))
- if (!checkForOK(1000, (const char*) F("0.0.0.0"), true,false))
- ipOK = true;
- } else { // Should this really be "else" here /haba
-
- if (!ipOK) {
-
- // Older ES versions have AT+CWJAP, newer ones have AT+CWJAP_CUR and AT+CWHOSTNAME
- StringFormatter::send(wifiStream, F("AT+CWJAP?\r\n"));
- if (checkForOK(2000, OK_SEARCH, true)) {
- oldCmd=true;
- while (wifiStream->available()) StringFormatter::printEscape( wifiStream->read()); /// THIS IS A DIAG IN DISGUISE
+ if (strncmp_P(yourNetwork, (const char*)SSid, 13) == 0 || strncmp_P("", (const char*)SSid, 13) == 0) {
+ if (strncmp_P(yourNetwork, (const char*)password, 13) == 0) {
+ // If the source code looks unconfigured, check if the
+ // ESP8266 is preconfigured in station mode.
+ // We check the first 13 chars of the SSid and the password
+ // give a preconfigured ES8266 a chance to connect to a router
+ // typical connect time approx 7 seconds
+ delay(8000);
+ StringFormatter::send(wifiStream, F("AT+CIFSR\r\n"));
+ if (checkForOK(5000, F("+CIFSR:STAIP"), true,false))
+ if (!checkForOK(1000, F("0.0.0.0"), true,false))
+ ipOK = true;
+ }
+ } else {
+ // SSID was configured, so we assume station (client) mode.
+ if (oldCmd) {
// AT command early version supports CWJAP/CWSAP
- if (SSid) {
- StringFormatter::send(wifiStream, F("AT+CWJAP=\"%S\",\"%S\"\r\n"), SSid, password);
- ipOK = checkForOK(WIFI_CONNECT_TIMEOUT, OK_SEARCH, true);
- }
- DIAG(F("\n**\n"));
-
+ StringFormatter::send(wifiStream, F("AT+CWJAP=\"%S\",\"%S\"\r\n"), SSid, password);
+ ipOK = checkForOK(WIFI_CONNECT_TIMEOUT, true);
} else {
// later version supports CWJAP_CUR
-
StringFormatter::send(wifiStream, F("AT+CWHOSTNAME=\"%S\"\r\n"), hostname); // Set Host name for Wifi Client
- checkForOK(2000, OK_SEARCH, true); // dont care if not supported
+ checkForOK(2000, true); // dont care if not supported
- if (SSid) {
- StringFormatter::send(wifiStream, F("AT+CWJAP_CUR=\"%S\",\"%S\"\r\n"), SSid, password);
- ipOK = checkForOK(WIFI_CONNECT_TIMEOUT, OK_SEARCH, true);
- }
+ StringFormatter::send(wifiStream, F("AT+CWJAP_CUR=\"%S\",\"%S\"\r\n"), SSid, password);
+ ipOK = checkForOK(WIFI_CONNECT_TIMEOUT, true);
}
if (ipOK) {
// But we really only have the ESSID and password correct
- // Let's check for IP
+ // Let's check for IP (via DHCP)
ipOK = false;
StringFormatter::send(wifiStream, F("AT+CIFSR\r\n"));
- if (checkForOK(5000, (const char*) F("+CIFSR:STAIP"), true,false))
- if (!checkForOK(1000, (const char*) F("0.0.0.0"), true,false))
+ if (checkForOK(5000, F("+CIFSR:STAIP"), true,false))
+ if (!checkForOK(1000, F("0.0.0.0"), true,false))
ipOK = true;
}
- }
}
if (!ipOK) {
// If we have not managed to get this going in station mode, go for AP mode
- StringFormatter::send(wifiStream, F("AT+CWMODE=2\r\n")); // configure as AccessPoint.
- checkForOK(1000, OK_SEARCH, true); // Not always OK, sometimes "no change"
+// StringFormatter::send(wifiStream, F("AT+RST\r\n"));
+// checkForOK(1000, true); // Not always OK, sometimes "no change"
+
+ int i=0;
+ do {
+ // configure as AccessPoint. Try really hard as this is the
+ // last way out to get any Wifi connectivity.
+ StringFormatter::send(wifiStream, F("AT+CWMODE=2\r\n"));
+ } while (!checkForOK(1000+i*500, true) && i++<10);
+
+ while (wifiStream->available()) StringFormatter::printEscape( wifiStream->read()); /// THIS IS A DIAG IN DISGUISE
// Figure out MAC addr
- StringFormatter::send(wifiStream, F("AT+CIFSR\r\n"));
+ StringFormatter::send(wifiStream, F("AT+CIFSR\r\n")); // not TOMATO
// looking fpr mac addr eg +CIFSR:APMAC,"be:dd:c2:5c:6b:b7"
- if (checkForOK(5000, (const char*) F("+CIFSR:APMAC,\""), true,false)) {
+ if (checkForOK(5000, F("+CIFSR:APMAC,\""), true,false)) {
// Copy 17 byte mac address
for (int i=0; i<17;i++) {
while(!wifiStream->available());
macAddress[i]=wifiStream->read();
StringFormatter::printEscape(macAddress[i]);
}
+ } else {
+ memset(macAddress,'f',sizeof(macAddress));
}
char macTail[]={macAddress[9],macAddress[10],macAddress[12],macAddress[13],macAddress[15],macAddress[16],'\0'};
- if (oldCmd) {
- while (wifiStream->available()) StringFormatter::printEscape( wifiStream->read()); /// THIS IS A DIAG IN DISGUISE
+ checkForOK(1000, true, false); // suck up remainder of AT+CIFSR
+
+ i=0;
+ do {
+ if (strncmp_P(yourNetwork, (const char*)password, 13) == 0) {
+ // unconfigured
+ StringFormatter::send(wifiStream, F("AT+CWSAP%s=\"DCCEX_%s\",\"PASS_%s\",%d,4\r\n"),
+ oldCmd ? "" : "_CUR", macTail, macTail, channel);
+ } else {
+ // password configured by user
+ StringFormatter::send(wifiStream, F("AT+CWSAP%s=\"DCCEX_%s\",\"%S\",%d,4\r\n"), oldCmd ? "" : "_CUR",
+ macTail, password, channel);
+ }
+ } while (!checkForOK(WIFI_CONNECT_TIMEOUT, true) && i++<2); // do twice if necessary but ignore failure as AP mode may still be ok
+ if (i >= 2)
+ DIAG(F("\nWarning: Setting AP SSID and password failed\n")); // but issue warning
- int i=0;
- do {
- if (strncmp_P(yourNetwork, (const char*)password, 13) == 0) {
- // unconfigured
- StringFormatter::send(wifiStream, F("AT+CWSAP=\"DCCEX_%s\",\"PASS_%s\",1,4\r\n"), macTail, macTail);
- } else {
- // password configured by user
- StringFormatter::send(wifiStream, F("AT+CWSAP=\"DCCEX_%s\",\"%s\",1,4\r\n"), macTail, password);
- }
- } while (i++<2 && !checkForOK(WIFI_CONNECT_TIMEOUT, OK_SEARCH, true)); // do twice if necessary but ignore failure as AP mode may still be ok
- } else {
-
- StringFormatter::send(wifiStream, F("AT+CWSAP_CUR=\"DCCEX_%s\",\"PASS_%s\",1,4\r\n"), macTail, macTail);
- checkForOK(20000, OK_SEARCH, true); // can ignore failure as SSid mode may still be ok
-
+ if (!oldCmd) {
StringFormatter::send(wifiStream, F("AT+CIPRECVMODE=0\r\n"), port); // make sure transfer mode is correct
- checkForOK(2000, OK_SEARCH, true);
+ checkForOK(2000, true);
}
}
StringFormatter::send(wifiStream, F("AT+CIPSERVER=0\r\n")); // turn off tcp server (to clean connections before CIPMUX=1)
- checkForOK(1000, OK_SEARCH, true); // ignore result in case it already was off
+ checkForOK(1000, true); // ignore result in case it already was off
StringFormatter::send(wifiStream, F("AT+CIPMUX=1\r\n")); // configure for multiple connections
- if (!checkForOK(1000, OK_SEARCH, true)) return WIFI_DISCONNECTED;
+ if (!checkForOK(1000, true)) return WIFI_DISCONNECTED;
StringFormatter::send(wifiStream, F("AT+CIPSERVER=1,%d\r\n"), port); // turn on server on port
- if (!checkForOK(1000, OK_SEARCH, true)) return WIFI_DISCONNECTED;
+ if (!checkForOK(1000, true)) return WIFI_DISCONNECTED;
#endif //DONT_TOUCH_WIFI_CONF
StringFormatter::send(wifiStream, F("AT+CIFSR\r\n")); // Display ip addresses to the DIAG
- if (!checkForOK(1000, OK_SEARCH, true, false)) return WIFI_DISCONNECTED;
- DIAG(F("\nPORT=%d\n"),port);
+ if (!checkForOK(1000, F("IP,\"") , true, false)) return WIFI_DISCONNECTED;
+ // Copy the IP address
+ {
+ const byte MAX_IP_LENGTH=15;
+ char ipString[MAX_IP_LENGTH+1];
+ ipString[MAX_IP_LENGTH]='\0'; // protection against missing " character on end.
+ for(byte ipLen=0;ipLenavailable());
+ int ipChar=wifiStream->read();
+ StringFormatter::printEscape(ipChar);
+ if (ipChar=='"') {
+ ipString[ipLen]='\0';
+ break;
+ }
+ ipString[ipLen]=ipChar;
+ }
+ LCD(4,F("%s"),ipString); // There is not enough room on some LCDs to put a title to this
+ }
+ // suck up anything after the IP.
+ if (!checkForOK(1000, true, false)) return WIFI_DISCONNECTED;
+ LCD(5,F("PORT=%d\n"),port);
return WIFI_CONNECTED;
}
@@ -300,15 +325,19 @@ void WifiInterface::ATCommand(const byte * command) {
}
else {
StringFormatter:: send(wifiStream, F("AT+%s\r\n"), command);
- checkForOK(10000, OK_SEARCH, true);
+ checkForOK(10000, true);
}
}
-bool WifiInterface::checkForOK( const unsigned int timeout, const char * waitfor, bool echo, bool escapeEcho) {
+bool WifiInterface::checkForOK( const unsigned int timeout, bool echo, bool escapeEcho) {
+ return checkForOK(timeout,F("\r\nOK\r\n"),echo,escapeEcho);
+}
+
+bool WifiInterface::checkForOK( const unsigned int timeout, const FSH * waitfor, bool echo, bool escapeEcho) {
unsigned long startTime = millis();
- char const *locator = waitfor;
+ char *locator = (char *)waitfor;
DIAG(F("\nWifi Check: [%E]"), waitfor);
while ( millis() - startTime < timeout) {
while (wifiStream->available()) {
@@ -317,7 +346,7 @@ bool WifiInterface::checkForOK( const unsigned int timeout, const char * waitfor
if (escapeEcho) StringFormatter::printEscape( ch); /// THIS IS A DIAG IN DISGUISE
else DIAG(F("%c"), ch);
}
- if (ch != GETFLASH(locator)) locator = waitfor;
+ if (ch != GETFLASH(locator)) locator = (char *)waitfor;
if (ch == GETFLASH(locator)) {
locator++;
if (!GETFLASH(locator)) {
@@ -337,3 +366,5 @@ void WifiInterface::loop() {
WifiInboundHandler::loop();
}
}
+
+#endif
diff --git a/WifiInterface.h b/WifiInterface.h
index 191b56f..19f8a3a 100644
--- a/WifiInterface.h
+++ b/WifiInterface.h
@@ -20,7 +20,6 @@
#ifndef WifiInterface_h
#define WifiInterface_h
#include "FSH.h"
-#include "config.h"
#include "DCCEXParser.h"
#include
#include
@@ -35,23 +34,20 @@ public:
const FSH *wifiESSID,
const FSH *wifiPassword,
const FSH *hostname,
- const int port = 2560);
+ const int port,
+ const byte channel);
static void loop();
static void ATCommand(const byte *command);
-
+
private:
static wifiSerialState setup(Stream &setupStream, const FSH *SSSid, const FSH *password,
- const FSH *hostname, int port);
+ const FSH *hostname, int port, byte channel);
static Stream *wifiStream;
static DCCEXParser parser;
static wifiSerialState setup2(const FSH *SSSid, const FSH *password,
- const FSH *hostname, int port);
- static bool checkForOK(const unsigned int timeout, const char *waitfor, bool echo, bool escapeEcho = true);
+ const FSH *hostname, int port, byte channel);
+ static bool checkForOK(const unsigned int timeout, bool echo, bool escapeEcho = true);
+ static bool checkForOK(const unsigned int timeout, const FSH *waitfor, bool echo, bool escapeEcho = true);
static bool connected;
- static bool closeAfter;
- static byte loopstate;
- static int datalength;
- static int connectionId;
- static unsigned long loopTimeoutStart;
};
#endif
diff --git a/config.example.h b/config.example.h
index 4f3a2f1..768fae3 100644
--- a/config.example.h
+++ b/config.example.h
@@ -1,10 +1,9 @@
/**********************************************************************
-Config.h
-COPYRIGHT (c) 2013-2016 Gregg E. Berman
+config.h
COPYRIGHT (c) 2020 Fred Decker
-The configuration file for DCC++ EX Command Station
+The configuration file for DCC-EX Command Station
**********************************************************************/
@@ -52,10 +51,14 @@ The configuration file for DCC++ EX Command Station
// WIFI_SSID is the network name IF you want to use your existing home network.
// Do NOT change this if you want to use the WiFi in Access Point (AP) mode.
//
-// If you do NOT set the WIFI_SSID, the WiFi chip will first try
-// to connect to the previously configured network and if that fails
-// fall back to Access Point mode. The SSID of the AP will be
-// automatically set to DCCEX_*.
+// If you do NOT set the WIFI_SSID and do NOT set the WIFI_PASSWORD,
+// then the WiFi chip will first try to connect to the previously
+// configured network and if that fails fall back to Access Point mode.
+// The SSID of the AP will be automatically set to DCCEX_*.
+// If you DO set the WIFI_SSID then the WiFi chip will try to connect
+// to that (home) network in station (client) mode. If a WIFI_PASSWORD
+// is set (recommended), that password will be used for AP mode.
+// The AP mode password must be at least 8 characters long.
//
// Your SSID may not conain ``"'' (double quote, ASCII 0x22).
#define WIFI_SSID "Your network name"
@@ -69,6 +72,12 @@ The configuration file for DCC++ EX Command Station
// WIFI_HOSTNAME: You probably don't need to change this
#define WIFI_HOSTNAME "dccex"
//
+// WIFI_CHANNEL: If the line "#define ENABLE_WIFI true" is uncommented,
+// WiFi will be enabled (Mega only). The default channel is set to "1" whether
+// this line exists or not. If you need to use an alternate channel (we recommend
+// using only 1,6, or 11) you may change it here.
+#define WIFI_CHANNEL 1
+//
/////////////////////////////////////////////////////////////////////////////////////
//
// Wifi connect timeout in milliseconds. Default is 14000 (14 seconds). You only need
@@ -90,26 +99,6 @@ The configuration file for DCC++ EX Command Station
//
//#define IP_ADDRESS { 192, 168, 1, 200 }
-/////////////////////////////////////////////////////////////////////////////////////
-//
-// DEFINE MAC ADDRESS ARRAY FOR ETHERNET COMMUNICATIONS INTERFACE
-//
-// Uncomment to use with Ethernet Shields
-//
-// Ethernet Shields do not have have a MAC address in hardware. There may be one on
-// a sticker on the Shield that you should use. Otherwise choose one of the ones below
-// Be certain that no other device on your network has this same MAC address!
-//
-// 52:b8:8a:8e:ce:21
-// e3:e9:73:e1:db:0d
-// 54:2b:13:52:ac:0c
-
-// NOTE: This is not used with ESP8266 WiFi modules.
-
-//#define MAC_ADDRESS { 0x52, 0xB8, 0x8A, 0x8E, 0xCE, 0x21 } // MAC address of your networking card found on the sticker on your card or take one from above
-
-//
-// #define MAC_ADDRESS { 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xEF }
/////////////////////////////////////////////////////////////////////////////////////
//
diff --git a/defines.h b/defines.h
index 2234761..a85e51c 100644
--- a/defines.h
+++ b/defines.h
@@ -21,10 +21,13 @@
////////////////////////////////////////////////////////////////////////////////
//
// 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 ENABLE_WIFI && (defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560) || defined(ARDUINO_SAMD_ZERO) || defined(ARDUINO_AVR_UNO_WIFI_REV2))
#define WIFI_ON true
+#ifndef WIFI_CHANNEL
+#define WIFI_CHANNEL 1
+#endif
#else
#define WIFI_ON false
#endif
diff --git a/examples/advanced/CommandStation-EX.ino b/examples/advanced/CommandStation-EX.ino
deleted file mode 100644
index b7d10c0..0000000
--- a/examples/advanced/CommandStation-EX.ino
+++ /dev/null
@@ -1,152 +0,0 @@
-/*
- * © 2020, Chris Harlow. All rights reserved.
- *
- * This file is a demonstattion of calling the DCC-EX API
- */
-
-
-
-#include "DCCEX.h"
-
-#ifdef ARDUINO_AVR_UNO
- #include
- SoftwareSerial Serial1(15,16); // YOU must get these pins correct to use Wifi on a UNO
- #define WIFI_BAUD 9600
-#else
- #define WIFI_BAUD 115200
-#endif
-
-// this code is here to demonstrate use of the DCC API and other techniques
-
-// myFilter is an example of an OPTIONAL command filter used to intercept < > commands from
-// the usb or wifi streamm. It demonstrates how a command may be intercepted
-// or even a new command created without having to break open the API library code.
-// The filter is permitted to use or modify the parameter list before passing it on to
-// the standard parser. By setting the opcode to 0, the standard parser will
-// just ignore the command on the assumption that you have already handled it.
-//
-// The filter must be enabled by calling the DCC EXParser::setFilter method, see use in setup().
-
-void myComandFilter(Print * stream, byte & opcode, byte & paramCount, int p[]) {
- (void)stream; // avoid compiler warning if we don't access this parameter
- switch (opcode) {
- case '!': // Create a bespoke new command to clear all loco reminders or specific locos e.g
- if (paramCount==0) DCC::forgetAllLocos();
- else for (int i=0;iThis is my HTTP filter responding.