1
0
mirror of https://github.com/DCC-EX/CommandStation-EX.git synced 2024-11-22 15:46:14 +01:00

Compare commits

...

43 Commits

Author SHA1 Message Date
Kcsmith0708
ffcbc6b70e
Merge 2c133da140 into dc481a2f0c 2024-09-26 06:28:39 +00:00
Asbelos
dc481a2f0c EthernetInterface 2024-09-23 09:34:26 +01:00
Asbelos
692f97e480 Merge branch 'devel_fozzie2' into devel 2024-09-23 09:16:39 +01:00
Asbelos
7fb7751f19 Merge branch 'devel_fozzie2' of https://github.com/DCC-EX/CommandStation-EX into devel_fozzie2 2024-09-23 08:50:13 +01:00
Asbelos
546ddd8139 STRCHR_P for sensorcam 2024-09-23 08:42:49 +01:00
Harald Barth
4aa353edbc version 5.2.79 2024-09-22 21:03:36 +02:00
Harald Barth
c1d6ee2804 Merge branch 'wifirestart' into devel 2024-09-22 21:01:16 +02:00
Harald Barth
14360b4198 serial manager loop that handles quoted strings 2024-09-22 20:58:17 +02:00
Harald Barth
dd898d3c16 WiFiESP32 reconfig prototype 2024-09-22 20:58:17 +02:00
Asbelos
277431e84c NeoPixel support
commit 2bbb5c1119
Author: Asbelos <asbelos@btinternet.com>
Date:   Fri Sep 20 12:13:21 2024 +0100

    EXRAIL use neopixel range instead of loop

commit 3aabb51888
Author: Asbelos <asbelos@btinternet.com>
Date:   Wed Sep 18 17:06:00 2024 +0100

    Neopixel signals with blue-tint

    See Release Notes file

commit 8e6fe6df21
Author: Asbelos <asbelos@btinternet.com>
Date:   Thu Sep 12 08:35:26 2024 +0100

    HAL write range

commit 66e57b5ab2
Author: Asbelos <asbelos@btinternet.com>
Date:   Sun Sep 8 09:26:37 2024 +0100

    Killblink on neopixel set.

commit 360c426675
Merge: dd16e0d b026417
Author: Asbelos <asbelos@btinternet.com>
Date:   Sat Sep 7 16:45:29 2024 +0100

    Merge branch 'devel' into devel-pauls-i2c-devices

commit dd16e0da97
Author: Asbelos <asbelos@btinternet.com>
Date:   Sat Sep 7 13:00:26 2024 +0100

    Notes

commit e823db3d24
Author: Asbelos <asbelos@btinternet.com>
Date:   Sat Sep 7 11:16:30 2024 +0100

    Neopixel change to 8,8,8

commit d3d6cc97fb
Author: Asbelos <asbelos@btinternet.com>
Date:   Fri Sep 6 13:25:44 2024 +0100

    Neopixel <o> cmd

commit 03d8d5f93d
Author: Asbelos <asbelos@btinternet.com>
Date:   Fri Sep 6 08:08:18 2024 +0100

    Its working!!

commit 235f3c82b5
Author: Asbelos <asbelos@btinternet.com>
Date:   Thu Sep 5 22:02:29 2024 +0100

    Update IO_NeoPixel.h

commit 530b77bbab
Author: Asbelos <asbelos@btinternet.com>
Date:   Tue Sep 3 15:04:40 2024 +0100

    NEOPIXEL driver and macros

commit 2a895fbbd5
Author: Asbelos <asbelos@btinternet.com>
Date:   Tue Sep 3 11:26:17 2024 +0100

    First compile neopixel driver

commit c6f2db7909
Merge: a7df84b 7395aa4
Author: Asbelos <asbelos@btinternet.com>
Date:   Tue Sep 3 10:07:12 2024 +0100

    Merge branch 'devel' into devel-pauls-i2c-devices

commit a7df84b01c
Author: Asbelos <asbelos@btinternet.com>
Date:   Tue Sep 3 09:56:05 2024 +0100

    NEOPIXEL EXRAIL

commit ead6e5afa1
Author: Asbelos <asbelos@btinternet.com>
Date:   Tue Sep 3 09:55:36 2024 +0100

    NEOPIXEL EXRAIL

commit 0cb175544e
Author: pmantoine <pma-github@milleng.com.au>
Date:   Sat Feb 24 17:29:10 2024 +0800

    More TCA8418

commit 2082051801
Author: pmantoine <pma-github@milleng.com.au>
Date:   Sat Feb 24 13:02:34 2024 +0800

    TCA8418 initial HAL driver scaffolding
2024-09-22 12:37:38 +01:00
Harald Barth
fe2f705fa9 version 5.2.77 2024-09-12 14:22:36 +02:00
Harald Barth
2606d73d93 Implement WiThrottle "force function" subcommand "f" 2024-09-12 14:20:24 +02:00
Harald Barth
ec42c09e06 Merge branch 'devel_fozzie2' of https://github.com/DCC-EX/CommandStation-EX into devel_fozzie2 2024-09-11 11:25:21 +02:00
Harald Barth
4ab77c21ed tag 2024-09-11 11:21:32 +02:00
Harald Barth
b53384ab51 If anyone ever wants to run a SABERTOOTH motor controller from a Mega2560 2024-09-07 23:31:02 +02:00
Harald Barth
b026417efb EXTRAIL: Propagate a failed loco addr read to EXRAIL so it can be used as IFLOCO(-1) 2024-09-06 09:28:40 +02:00
Harald Barth
7ffbd9d0e8 Use port variable 2024-09-05 13:01:54 +02:00
Harald Barth
6fa5511670 version 2024-09-04 09:13:52 +02:00
Harald Barth
c07ac38ab1 EXRAIL: Catch CV read errors in the callback 2024-09-04 09:11:51 +02:00
Asbelos
4174c2a4ab Merge branch 'devel_fozzie2' of https://github.com/DCC-EX/CommandStation-EX into devel_fozzie2 2024-08-30 09:34:25 +01:00
pmantoine
30236f9b36 STM32 Ethernet fixed 2024-08-30 11:52:27 +08:00
Harald Barth
7395aa4af8 version 2024-08-29 13:46:44 +02:00
Harald Barth
2397b773d7 Bugfix: Enable CommandDistributor even for serials 4 to 6 2024-08-29 13:44:51 +02:00
Harald Barth
9a08f2df63 ESP32: Make Serial2 possible for commands 2024-08-29 13:41:37 +02:00
Asbelos
8245208b2b stm32 compiles 2024-08-25 17:26:33 +01:00
Asbelos
4ed2ee9adc mDNS restored on mega 2024-08-25 16:50:49 +01:00
Asbelos
06a353cfa0 stm32 merge (mdns disabled} 2024-08-25 16:29:59 +01:00
Harald Barth
dfe9e6b69f platformio eth debug target 2024-08-25 17:01:58 +02:00
Asbelos
4d84eccac3 LCD and link warning 2024-08-20 19:51:45 +01:00
Harald Barth
edb02a00ce allow static IP (again) 2024-08-19 08:59:32 +02:00
Asbelos
5db19a0fb8 Ethgernet simplification 2024-08-18 20:32:05 +01:00
Harald Barth
b62661c337 tag 2024-08-17 23:09:09 +02:00
Harald Barth
048ba3fd1e replace socket.connected() with check for return value of socket.read() 2024-08-17 20:18:59 +02:00
Harald Barth
c8c3697fa0 write buffer 2024-08-09 15:02:11 +02:00
Harald Barth
8c3c5dfe33 do not flush 2024-08-09 14:34:30 +02:00
Harald Barth
92288603bf do not available, just try to read 2024-08-09 12:01:53 +02:00
Harald Barth
80c8b3ef62 better name 2024-08-09 11:57:54 +02:00
Harald Barth
127f3acce5 send whole outbuffer 2024-08-09 11:46:33 +02:00
Harald Barth
690c629e6d looptimer more diag in EthernetInterface 2024-08-09 09:16:56 +02:00
Harald Barth
e328ea5c5d Merge branch 'devel' into devel-fozzie 2024-08-08 10:52:50 +02:00
Harald Barth
923b031d06 Gittag 2024-08-07 21:14:07 +02:00
Harald Barth
7e29011d63 looptimer test 1 2024-08-07 21:13:44 +02:00
Kcsmith0708
2c133da140
Update DCC.h
Commented MAX_LOCOS
Lowered the default Max for Uno CS from 30 to 10
2024-04-12 10:37:04 -04:00
27 changed files with 1310 additions and 346 deletions

View File

@ -37,7 +37,7 @@ int16_t lastclocktime;
int8_t lastclockrate;
#if WIFI_ON || ETHERNET_ON || defined(SERIAL1_COMMANDS) || defined(SERIAL2_COMMANDS) || defined(SERIAL3_COMMANDS)
#if WIFI_ON || ETHERNET_ON || defined(SERIAL1_COMMANDS) || defined(SERIAL2_COMMANDS) || defined(SERIAL3_COMMANDS) || defined(SERIAL4_COMMANDS) || defined(SERIAL5_COMMANDS) || defined(SERIAL6_COMMANDS)
// use a buffer to allow broadcast
StringBuffer * CommandDistributor::broadcastBufferWriter=new StringBuffer();
template<typename... Targs> void CommandDistributor::broadcastReply(clientType type, Targs... msg){

View File

@ -141,6 +141,23 @@ void setup()
CommandDistributor::broadcastPower();
}
/**************** for future reference
void looptimer(unsigned long timeout, const FSH* message)
{
static unsigned long lasttimestamp = 0;
unsigned long now = micros();
if (timeout != 0) {
unsigned long diff = now - lasttimestamp;
if (diff > timeout) {
DIAG(message);
DIAG(F("DeltaT=%L"), diff);
lasttimestamp = micros();
return;
}
}
lasttimestamp = now;
}
*********************************************/
void loop()
{
// The main sketch has responsibilities during loop()
@ -148,14 +165,15 @@ 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
#ifndef ARDUINO_ARCH_ESP32
#if WIFI_ON
WifiInterface::loop();
#endif //WIFI_ON
#else //ARDUINO_ARCH_ESP32
#ifndef WIFI_TASK_ON_CORE0

6
DCC.h
View File

@ -43,9 +43,9 @@ const uint16_t LONG_ADDR_MARKER = 0x4000;
// Allocations with memory implications..!
// Base system takes approx 900 bytes + 8 per loco. Turnouts, Sensors etc are dynamically created
#if defined(HAS_ENOUGH_MEMORY)
const byte MAX_LOCOS = 50;
#else
const byte MAX_LOCOS = 30;
const byte MAX_LOCOS = 50; // Default 50 for Mega2560, Increase for ESP32 and STM32 Nucleo
#else // Adjust Max Locos as needed.
const byte MAX_LOCOS = 10; // Lower Max Loco for Uno CS, Recommended as a JMRI DecoderPro Programming Station
#endif
class DCC

View File

@ -72,7 +72,7 @@ Once a new OPCODE is decided upon, update this list.
M, Write DCC packet
n, Reserved for SensorCam
N, Reserved for Sensorcam
o,
o, Neopixel driver (see also IO_NeoPixel.h)
O, Output broadcast
p, Broadcast power state
P, Write DCC packet
@ -117,6 +117,9 @@ Once a new OPCODE is decided upon, update this list.
#include "Turntables.h"
#include "version.h"
#include "KeywordHasher.h"
#ifdef ARDUINO_ARCH_ESP32
#include "WifiESP32.h"
#endif
// This macro can't be created easily as a portable function because the
// flashlist requires a far pointer for high flash access.
@ -140,12 +143,12 @@ byte DCCEXParser::stashTarget=0;
// Non-DCC things like turnouts, pins and sensors are handled in additional JMRI interface classes.
int16_t DCCEXParser::splitValues(int16_t result[MAX_COMMAND_PARAMS], const byte *cmd, bool usehex)
int16_t DCCEXParser::splitValues(int16_t result[MAX_COMMAND_PARAMS], byte *cmd, bool usehex)
{
byte state = 1;
byte parameterCount = 0;
int16_t runningValue = 0;
const byte *remainingCmd = cmd + 1; // skips the opcode
byte *remainingCmd = cmd + 1; // skips the opcode
bool signNegative = false;
// clear all parameters in case not enough found
@ -155,7 +158,6 @@ int16_t DCCEXParser::splitValues(int16_t result[MAX_COMMAND_PARAMS], const byte
while (parameterCount < MAX_COMMAND_PARAMS)
{
byte hot = *remainingCmd;
switch (state)
{
@ -169,7 +171,22 @@ int16_t DCCEXParser::splitValues(int16_t result[MAX_COMMAND_PARAMS], const byte
state = 2;
continue;
case 2: // checking sign
case 2: // checking sign or quoted string
#ifdef HAS_ENOUGH_MEMORY
if (hot == '"') {
// this inserts an extra parameter 0x7777 in front
// of each string parameter as a marker that can
// be checked that a string parameter follows
// This clashes of course with the real value
// 0x7777 which we hope is used seldom
result[parameterCount] = (int16_t)0x7777;
parameterCount++;
result[parameterCount] = (int16_t)(remainingCmd - cmd + 1);
parameterCount++;
state = 4;
break;
}
#endif
signNegative = false;
runningValue = 0;
state = 3;
@ -200,6 +217,16 @@ int16_t DCCEXParser::splitValues(int16_t result[MAX_COMMAND_PARAMS], const byte
parameterCount++;
state = 1;
continue;
#ifdef HAS_ENOUGH_MEMORY
case 4: // skipover text
if (hot == '\0') // We did run to end of buffer without finding the "
return -1;
if (hot == '"') {
*remainingCmd = '\0'; // overwrite " in command buffer with the end-of-string
state = 1;
}
break;
#endif
}
remainingCmd++;
}
@ -394,7 +421,36 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
return;
break;
case 'z': // direct pin manipulation
#ifndef IO_NO_HAL
case 'o': // Neopixel pin manipulation
if (p[0]==0) break;
{
VPIN vpin=p[0]>0 ? p[0]:-p[0];
bool setON=p[0]>0;
if (params==1) { // <o [-]vpin>
IODevice::write(vpin,setON);
return;
}
if (params==2) { // <o [-]vpin count>
IODevice::writeRange(vpin,setON,p[1]);
return;
}
if (params==4 || params==5) { // <z [-]vpin r g b [count]>
auto count=p[4]?p[4]:1;
if (p[1]<0 || p[1]>0xFF) break;
if (p[2]<0 || p[2]>0xFF) break;
if (p[3]<0 || p[3]>0xFF) break;
// strange parameter mangling... see IO_NeoPixel.h NeoPixel::_writeAnalogue
int colour_RG=(p[1]<<8) | p[2];
uint16_t colour_B=p[3];
IODevice::writeAnalogueRange(vpin,colour_RG,setON,colour_B,count);
return;
}
}
break;
#endif
case 'z': // direct pin manipulation
if (p[0]==0) break;
if (params==1) { // <z vpin | -vpin>
if (p[0]>0) IODevice::write(p[0],HIGH);
@ -616,9 +672,22 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
StringFormatter::send(stream, F("\n"));
return;
case 'C': // CONFIG <C [params]>
if (parseC(stream, params, p))
return;
break;
#if defined(ARDUINO_ARCH_ESP32)
// currently this only works on ESP32
#if defined(HAS_ENOUGH_MEMORY)
if (p[0] == "WIFI"_hk) { // <C WIFI SSID PASSWORD>
if (params != 5) // the 5 params 0 to 4 are (kinda): WIFI_hk 0x7777 &SSID 0x7777 &PASSWORD
break;
if (p[1] == 0x7777 && p[3] == 0x7777) {
WifiESP::setup((const char*)(com + p[2]), (const char*)(com + p[4]), WIFI_HOSTNAME, IP_PORT, WIFI_CHANNEL, WIFI_FORCE_AP);
}
return;
}
#endif
#endif //ESP32
if (parseC(stream, params, p))
return;
break;
#ifndef DISABLE_DIAG
case 'D': // DIAG <D [params]>
if (parseD(stream, params, p))
@ -1111,8 +1180,7 @@ bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) {
}
return true;
#endif
default: // invalid/unknown
default: // invalid/unknown
break;
}
return false;

View File

@ -43,7 +43,7 @@ struct DCCEXParser
private:
static const int16_t MAX_BUFFER=50; // longest command sent in
static int16_t splitValues( int16_t result[MAX_COMMAND_PARAMS], const byte * command, bool usehex);
static int16_t splitValues( int16_t result[MAX_COMMAND_PARAMS], byte * command, bool usehex);
static bool parseT(Print * stream, int16_t params, int16_t p[]);
static bool parseZ(Print * stream, int16_t params, int16_t p[]);

View File

@ -73,6 +73,7 @@ RMFT2 * RMFT2::pausingTask=NULL; // Task causing a PAUSE.
byte RMFT2::flags[MAX_FLAGS];
Print * RMFT2::LCCSerial=0;
LookList * RMFT2::routeLookup=NULL;
LookList * RMFT2::signalLookup=NULL;
LookList * RMFT2::onThrowLookup=NULL;
LookList * RMFT2::onCloseLookup=NULL;
LookList * RMFT2::onActivateLookup=NULL;
@ -207,16 +208,28 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
// Second pass startup, define any turnouts or servos, set signals red
// add sequences onRoutines to the lookups
if (compileFeatures & FEATURE_SIGNAL) {
onRedLookup=LookListLoader(OPCODE_ONRED);
onAmberLookup=LookListLoader(OPCODE_ONAMBER);
onGreenLookup=LookListLoader(OPCODE_ONGREEN);
for (int sigslot=0;;sigslot++) {
int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8);
if (sighandle==0) break; // end of signal list
VPIN sigid = sighandle & SIGNAL_ID_MASK;
doSignal(sigid, SIGNAL_RED);
}
}
// Load the signal lookup with slot numbers in the signal table
int signalCount=0;
for (int16_t slot=0;;slot++) {
SIGNAL_DEFINITION signal=getSignalSlot(slot);
DIAG(F("Signal s=%d id=%d t=%d"),slot,signal.id,signal.type);
if (signal.type==sigtypeNoMoreSignals) break;
if (signal.type==sigtypeContinuation) continue;
signalCount++;
}
signalLookup=new LookList(signalCount);
for (int16_t slot=0;;slot++) {
SIGNAL_DEFINITION signal=getSignalSlot(slot);
if (signal.type==sigtypeNoMoreSignals) break;
if (signal.type==sigtypeContinuation) continue;
signalLookup->add(signal.id,slot);
doSignal(signal.id, SIGNAL_RED);
}
}
int progCounter;
for (progCounter=0;; SKIPOP){
@ -478,10 +491,15 @@ bool RMFT2::skipIfBlock() {
/* static */ void RMFT2::readLocoCallback(int16_t cv) {
if (cv <= 0) {
DIAG(F("CV read error"));
progtrackLocoId = -1;
return;
}
if (cv & LONG_ADDR_MARKER) { // maker bit indicates long addr
progtrackLocoId = cv ^ LONG_ADDR_MARKER; // remove marker bit to get real long addr
if (progtrackLocoId <= HIGHEST_SHORT_ADDR ) { // out of range for long addr
DIAG(F("Long addr %d <= %d unsupported\n"), progtrackLocoId, HIGHEST_SHORT_ADDR);
DIAG(F("Long addr %d <= %d unsupported"), progtrackLocoId, HIGHEST_SHORT_ADDR);
progtrackLocoId = -1;
}
} else {
@ -921,11 +939,10 @@ void RMFT2::loop2() {
delayMe(100);
return; // still waiting for callback
}
if (progtrackLocoId<0) {
kill(F("No Loco Found"),progtrackLocoId);
return; // still waiting for callback
}
// At failed read will result in loco == -1
// which is intended so it can be checked
// from within EXRAIL
loco=progtrackLocoId;
speedo=0;
forward=true;
@ -997,8 +1014,18 @@ void RMFT2::loop2() {
return;
}
break;
#ifndef IO_NO_HAL
case OPCODE_NEOPIXEL:
// OPCODE_NEOPIXEL,V([-]vpin),OPCODE_PAD,V(colour_RG),OPCODE_PAD,V(colour_B),OPCODE_PAD,V(count)
{
VPIN vpin=operand>0?operand:-operand;
auto count=getOperand(3);
killBlinkOnVpin(vpin,count);
IODevice::writeAnalogueRange(vpin,getOperand(1),operand>0,getOperand(2),count);
}
break;
case OPCODE_WAITFORTT: // OPCODE_WAITFOR,V(turntable_id)
if (Turntable::ttMoving(operand)) {
delayMe(100);
@ -1120,26 +1147,11 @@ void RMFT2::kill(const FSH * reason, int operand) {
delete this;
}
int16_t RMFT2::getSignalSlot(int16_t id) {
if (id > 0) {
int sigslot = 0;
int16_t sighandle = 0;
// Trundle down the signal list until we reach the end
while ((sighandle = GETHIGHFLASHW(RMFT2::SignalDefinitions, sigslot * 8)) != 0)
{
// sigid is the signal id used in RED/AMBER/GREEN macro
// for a LED signal it will be same as redpin
// but for a servo signal it will also have SERVO_SIGNAL_FLAG set.
VPIN sigid = sighandle & SIGNAL_ID_MASK;
if (sigid == (VPIN)id) // cast to keep compiler happy but id is positive
return sigslot; // found it
sigslot++; // keep looking
};
}
// If we got here, we did not find the signal
DIAG(F("EXRAIL Signal %d not defined"), id);
return -1;
SIGNAL_DEFINITION RMFT2::getSignalSlot(int16_t slot) {
SIGNAL_DEFINITION signal;
COPYHIGHFLASH(&signal,SignalDefinitions,slot*sizeof(SIGNAL_DEFINITION),sizeof(SIGNAL_DEFINITION));
return signal;
}
/* static */ void RMFT2::doSignal(int16_t id,char rag) {
@ -1152,81 +1164,97 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
else if (rag==SIGNAL_GREEN) onGreenLookup->handleEvent(F("GREEN"),id);
else onAmberLookup->handleEvent(F("AMBER"),id);
int16_t sigslot=getSignalSlot(id);
auto sigslot=signalLookup->find(id);
if (sigslot<0) return;
// keep track of signal state
setFlag(sigslot,rag,SIGNAL_MASK);
// Correct signal definition found, get the rag values
int16_t sigpos=sigslot*8;
int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos);
VPIN redpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+2);
VPIN amberpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+4);
VPIN greenpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+6);
//if (diag) DIAG(F("signal %d %d %d %d %d"),sigid,id,redpin,amberpin,greenpin);
VPIN sigtype=sighandle & ~SIGNAL_ID_MASK;
VPIN sigid = sighandle & SIGNAL_ID_MASK;
if (sigtype == SERVO_SIGNAL_FLAG) {
// A servo signal, the pin numbers are actually servo positions
// Note, setting a signal to a zero position has no effect.
int16_t servopos= rag==SIGNAL_RED? redpin: (rag==SIGNAL_GREEN? greenpin : amberpin);
auto signal=getSignalSlot(sigslot);
switch (signal.type) {
case sigtypeSERVO:
{
auto servopos = rag==SIGNAL_RED? signal.redpin: (rag==SIGNAL_GREEN? signal.greenpin : signal.amberpin);
//if (diag) DIAG(F("sigA %d %d"),id,servopos);
if (servopos!=0) IODevice::writeAnalogue(id,servopos,PCA9685::Bounce);
return;
}
}
if (sigtype== DCC_SIGNAL_FLAG) {
case sigtypeDCC:
{
// redpin,amberpin are the DCC addr,subaddr
DCC::setAccessory(redpin,amberpin, rag!=SIGNAL_RED);
DCC::setAccessory(signal.redpin,signal.amberpin, rag!=SIGNAL_RED);
return;
}
if (sigtype== DCCX_SIGNAL_FLAG) {
case sigtypeDCCX:
{
// 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, value);
auto value=signal.redpin;
if (rag==SIGNAL_AMBER) value=signal.amberpin;
if (rag==SIGNAL_GREEN) value=signal.greenpin;
DCC::setExtendedAccessory(id, value);
return;
}
case sigtypeNEOPIXEL:
{
// redpin,amberpin,greenpin are the 3 RG values but with no blue permitted. . (code limitation hack)
auto colour_RG=signal.redpin;
if (rag==SIGNAL_AMBER) colour_RG=signal.amberpin;
if (rag==SIGNAL_GREEN) colour_RG=signal.greenpin;
// blue channel is in followng signal slot (a continuation)
auto signal2=getSignalSlot(sigslot+1);
auto colour_B=signal2.redpin;
if (rag==SIGNAL_AMBER) colour_B=signal2.amberpin;
if (rag==SIGNAL_GREEN) colour_B=signal2.greenpin;
IODevice::writeAnalogue(id, colour_RG,true,colour_B);
return;
}
case sigtypeSIGNAL:
case sigtypeSIGNALH:
{
// LED or similar 3 pin signal, (all pins zero would be a virtual signal)
// If amberpin is zero, synthesise amber from red+green
const byte SIMAMBER=0x00;
if (rag==SIGNAL_AMBER && (amberpin==0)) rag=SIMAMBER; // special case this func only
if (rag==SIGNAL_AMBER && (signal.amberpin==0)) rag=SIMAMBER; // special case this func only
// Manage invert (HIGH on) pins
bool aHigh=sighandle & ACTIVE_HIGH_SIGNAL_FLAG;
bool aHigh=signal.type==sigtypeSIGNALH;
// set the three pins
if (redpin) {
if (signal.redpin) {
bool redval=(rag==SIGNAL_RED || rag==SIMAMBER);
if (!aHigh) redval=!redval;
killBlinkOnVpin(redpin);
IODevice::write(redpin,redval);
killBlinkOnVpin(signal.redpin);
IODevice::write(signal.redpin,redval);
}
if (amberpin) {
if (signal.amberpin) {
bool amberval=(rag==SIGNAL_AMBER);
if (!aHigh) amberval=!amberval;
killBlinkOnVpin(amberpin);
IODevice::write(amberpin,amberval);
killBlinkOnVpin(signal.amberpin);
IODevice::write(signal.amberpin,amberval);
}
if (greenpin) {
if (signal.greenpin) {
bool greenval=(rag==SIGNAL_GREEN || rag==SIMAMBER);
if (!aHigh) greenval=!greenval;
killBlinkOnVpin(greenpin);
IODevice::write(greenpin,greenval);
killBlinkOnVpin(signal.greenpin);
IODevice::write(signal.greenpin,greenval);
}
}
case sigtypeVIRTUAL: break;
case sigtypeContinuation: break;
case sigtypeNoMoreSignals: break;
}
}
/* static */ bool RMFT2::isSignal(int16_t id,char rag) {
if (!(compileFeatures & FEATURE_SIGNAL)) return false;
int16_t sigslot=getSignalSlot(id);
int16_t sigslot=signalLookup->find(id);
if (sigslot<0) return false;
return (flags[sigslot] & SIGNAL_MASK) == rag;
}
@ -1238,26 +1266,23 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
// 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);
auto sigslot=signalLookup->find(address);
if (sigslot<0) return false; // this is not a defined signal
int16_t sigpos=sigslot*8;
int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos);
VPIN sigtype=sighandle & ~SIGNAL_ID_MASK;
VPIN sigid = sighandle & SIGNAL_ID_MASK;
if (sigtype!=DCCX_SIGNAL_FLAG) return false; // not a DCCX signal
auto signal=getSignalSlot(sigslot);
if (signal.type!=sigtypeDCCX) 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);
if (aspect==signal.redpin) {
doSignal(address,SIGNAL_RED);
return true;
}
if (aspect==GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+4)) {
doSignal(sigid,SIGNAL_AMBER);
if (aspect==signal.amberpin) {
doSignal(address,SIGNAL_AMBER);
return true;
}
if (aspect==GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+6)) {
doSignal(sigid,SIGNAL_GREEN);
if (aspect==signal.greenpin) {
doSignal(address,SIGNAL_GREEN);
return true;
}
@ -1311,19 +1336,24 @@ void RMFT2::powerEvent(int16_t track, bool overload) {
// This function is used when setting pins so that a SET or RESET
// will cause any blink task on that pin to terminate.
// It will be compiled out of existence if no BLINK feature is used.
void RMFT2::killBlinkOnVpin(VPIN pin) {
void RMFT2::killBlinkOnVpin(VPIN pin, uint16_t count) {
if (!(compileFeatures & FEATURE_BLINK)) return;
RMFT2 * stoptask=loopTask; // stop when we get back to here
RMFT2 * task=loopTask;
VPIN lastPin=pin+count-1;
while(task) {
auto nextTask=task->next;
if (
(task->blinkState==blink_high || task->blinkState==blink_low)
&& task->blinkPin==pin) {
&& task->blinkPin>=pin
&& task->blinkPin<=lastPin
) {
if (diag) DIAG(F("kill blink %d"),task->blinkPin,lastPin);
task->kill();
return;
}
task=task->next;
if (task==loopTask) return;
}
task=nextTask;
if (task==stoptask) return;
}
}

View File

@ -75,7 +75,8 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,OPCODE_TOGGLE_TURNOUT,
OPCODE_ROUTE_ACTIVE,OPCODE_ROUTE_INACTIVE,OPCODE_ROUTE_HIDDEN,
OPCODE_ROUTE_DISABLED,
OPCODE_STASH,OPCODE_CLEAR_STASH,OPCODE_CLEAR_ALL_STASH,OPCODE_PICKUP_STASH,
OPCODE_ONBUTTON,OPCODE_ONSENSOR,
OPCODE_ONBUTTON,OPCODE_ONSENSOR,
OPCODE_NEOPIXEL,
// OPcodes below this point are skip-nesting IF operations
// placed here so that they may be skipped as a group
// see skipIfBlock()
@ -109,6 +110,23 @@ enum BlinkState: byte {
blink_high, // blink task running with pin high
at_timeout // ATTIMEOUT timed out flag
};
enum SignalType {
sigtypeVIRTUAL,
sigtypeSIGNAL,
sigtypeSIGNALH,
sigtypeDCC,
sigtypeDCCX,
sigtypeSERVO,
sigtypeNEOPIXEL,
sigtypeContinuation, // neopixels require a second line
sigtypeNoMoreSignals
};
struct SIGNAL_DEFINITION {
SignalType type;
VPIN id;
VPIN redpin,amberpin,greenpin;
};
// Flag bits for compile time features.
static const byte FEATURE_SIGNAL= 0x80;
@ -170,12 +188,7 @@ class LookList {
static void rotateEvent(int16_t id, bool change);
static void powerEvent(int16_t track, bool overload);
static bool signalAspectEvent(int16_t address, byte aspect );
static const int16_t SERVO_SIGNAL_FLAG=0x4000;
static const int16_t ACTIVE_HIGH_SIGNAL_FLAG=0x2000;
static const int16_t DCC_SIGNAL_FLAG=0x1000;
static const int16_t DCCX_SIGNAL_FLAG=0x3000;
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 int16_t HIGHFLASH routeIdList[];
static const int16_t HIGHFLASH automationIdList[];
@ -189,7 +202,8 @@ class LookList {
static const FSH * getTurntablePositionDescription(int16_t turntableId, uint8_t positionId);
static void startNonRecursiveTask(const FSH* reason, int16_t id,int pc);
static bool readSensor(uint16_t sensorId);
static bool isSignal(int16_t id,char rag);
static bool isSignal(int16_t id,char rag);
static SIGNAL_DEFINITION getSignalSlot(int16_t slotno);
private:
static void ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]);
@ -199,7 +213,6 @@ private:
static bool getFlag(VPIN id,byte mask);
static int16_t progtrackLocoId;
static void doSignal(int16_t id,char rag);
static int16_t getSignalSlot(int16_t id);
static void setTurnoutHiddenState(Turnout * t);
#ifndef IO_NO_HAL
static void setTurntableHiddenState(Turntable * tto);
@ -207,7 +220,7 @@ private:
static LookList* LookListLoader(OPCODE op1,
OPCODE op2=OPCODE_ENDEXRAIL,OPCODE op3=OPCODE_ENDEXRAIL);
static uint16_t getOperand(int progCounter,byte n);
static void killBlinkOnVpin(VPIN pin);
static void killBlinkOnVpin(VPIN pin,uint16_t count=1);
static RMFT2 * loopTask;
static RMFT2 * pausingTask;
void delayMe(long millisecs);
@ -223,10 +236,11 @@ private:
static bool diag;
static const HIGHFLASH3 byte RouteCode[];
static const HIGHFLASH int16_t SignalDefinitions[];
static const HIGHFLASH SIGNAL_DEFINITION SignalDefinitions[];
static byte flags[MAX_FLAGS];
static Print * LCCSerial;
static LookList * routeLookup;
static LookList * signalLookup;
static LookList * onThrowLookup;
static LookList * onCloseLookup;
static LookList * onActivateLookup;

View File

@ -99,6 +99,9 @@
#undef LCCX
#undef LCN
#undef MOVETT
#undef NEOPIXEL
#undef NEOPIXEL_OFF
#undef NEOPIXEL_SIGNAL
#undef ACON
#undef ACOF
#undef ONACON
@ -269,6 +272,8 @@
#define LCN(msg)
#define MESSAGE(msg)
#define MOVETT(id,steps,activity)
#define NEOPIXEL(id,r,g,b,count...)
#define NEOPIXEL_SIGNAL(sigid,redcolour,ambercolour,greencolour)
#define ACON(eventid)
#define ACOF(eventid)
#define ONACON(eventid)

View File

@ -252,13 +252,13 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) {
// do the signals
// flags[n] represents the state of the nth signal in the table
for (int sigslot=0;;sigslot++) {
int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8);
if (sighandle==0) break; // end of signal list
VPIN sigid = sighandle & SIGNAL_ID_MASK;
byte flag=flags[sigslot] & SIGNAL_MASK; // obtain signal flags for this id
SIGNAL_DEFINITION slot=getSignalSlot(sigslot);
if (slot.type==sigtypeNoMoreSignals) break; // end of signal list
if (slot.type==sigtypeContinuation) continue; // continueation of previous line
byte flag=flags[sigslot] & SIGNAL_MASK; // obtain signal flags for this ids
StringFormatter::send(stream,F("\n%S[%d]"),
(flag == SIGNAL_RED)? F("RED") : (flag==SIGNAL_GREEN) ? F("GREEN") : F("AMBER"),
sigid);
slot.id);
}
}

View File

@ -71,6 +71,8 @@
//const byte TRACK_POWER_0=0, TRACK_POWER_OFF=0;
//const byte TRACK_POWER_1=1, TRACK_POWER_ON=1;
// NEOPIXEL RG generator for NEOPIXEL_SIGNAL
#define NeoRGB(red,green,blue) (((uint32_t)(red & 0xff)<<16) | ((uint32_t)(green & 0xff)<<8) | (uint32_t)(blue & 0xff))
// Pass 1 Implements aliases
#include "EXRAIL2MacroReset.h"
@ -180,6 +182,8 @@ bool exrailHalSetup() {
#define DCC_SIGNAL(id,addr,subaddr) | FEATURE_SIGNAL
#undef DCCX_SIGNAL
#define DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect) | FEATURE_SIGNAL
#undef NEOPIXEL_SIGNAL
#define NEOPIXEL_SIGNAL(sigid,redcolour,ambercolour,greencolour) | FEATURE_SIGNAL
#undef VIRTUAL_SIGNAL
#define VIRTUAL_SIGNAL(id) | FEATURE_SIGNAL
@ -421,21 +425,26 @@ const FSH * RMFT2::getRosterFunctions(int16_t id) {
// Pass 8 Signal definitions
#include "EXRAIL2MacroReset.h"
#undef SIGNAL
#define SIGNAL(redpin,amberpin,greenpin) redpin,redpin,amberpin,greenpin,
#define SIGNAL(redpin,amberpin,greenpin) {sigtypeSIGNAL,redpin,redpin,amberpin,greenpin},
#undef SIGNALH
#define SIGNALH(redpin,amberpin,greenpin) redpin | RMFT2::ACTIVE_HIGH_SIGNAL_FLAG,redpin,amberpin,greenpin,
#define SIGNALH(redpin,amberpin,greenpin) {sigtypeSIGNALH,redpin,redpin,amberpin,greenpin},
#undef SERVO_SIGNAL
#define SERVO_SIGNAL(vpin,redval,amberval,greenval) vpin | RMFT2::SERVO_SIGNAL_FLAG,redval,amberval,greenval,
#define SERVO_SIGNAL(vpin,redval,amberval,greenval) {sigtypeSERVO,vpin,redval,amberval,greenval},
#undef DCC_SIGNAL
#define DCC_SIGNAL(id,addr,subaddr) id | RMFT2::DCC_SIGNAL_FLAG,addr,subaddr,0,
#define DCC_SIGNAL(id,addr,subaddr) {sigtypeDCC,id,addr,subaddr,0},
#undef DCCX_SIGNAL
#define DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect) id | RMFT2::DCCX_SIGNAL_FLAG,redAspect,amberAspect,greenAspect,
#define DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect) {sigtypeDCCX,id,redAspect,amberAspect,greenAspect},
#undef NEOPIXEL_SIGNAL
#define NEOPIXEL_SIGNAL(id,redRGB,amberRGB,greenRGB) \
{sigtypeNEOPIXEL,id,((VPIN)((redRGB)>>8)), ((VPIN)((amberRGB)>>8)), ((VPIN)((greenRGB)>>8))},\
{sigtypeContinuation,id,((VPIN)((redRGB) & 0xff)), ((VPIN)((amberRGB) & 0xFF)), ((VPIN)((greenRGB) & 0xFF))},
#undef VIRTUAL_SIGNAL
#define VIRTUAL_SIGNAL(id) id,0,0,0,
#define VIRTUAL_SIGNAL(id) {sigtypeVIRTUAL,id,0,0,0},
const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = {
const HIGHFLASH SIGNAL_DEFINITION RMFT2::SignalDefinitions[] = {
#include "myAutomation.h"
0,0,0,0 };
{sigtypeNoMoreSignals,0,0,0,0}
};
// Pass 9 ONLCC/ ONMERG counter and lookup array
#include "EXRAIL2MacroReset.h"
@ -552,6 +561,12 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define LCN(msg) PRINT(msg)
#define MESSAGE(msg) PRINT(msg)
#define MOVETT(id,steps,activity) OPCODE_SERVO,V(id),OPCODE_PAD,V(steps),OPCODE_PAD,V(EXTurntable::activity),OPCODE_PAD,V(0),
#define NEOPIXEL(id,r,g,b,count...) OPCODE_NEOPIXEL,V(id),\
OPCODE_PAD,V(((r & 0xff)<<8) | (g & 0xff)),\
OPCODE_PAD,V((b & 0xff)),\
OPCODE_PAD,V(#count[0]?(count+0):1),
#define NEOPIXEL_SIGNAL(sigid,redcolour,ambercolour,greencolour)
#define ONACTIVATE(addr,subaddr) OPCODE_ONACTIVATE,V(addr<<2|subaddr),
#define ONACTIVATEL(linear) OPCODE_ONACTIVATE,V(linear+3),
#define ONAMBER(signal_id) OPCODE_ONAMBER,V(signal_id),

View File

@ -29,77 +29,93 @@
#include "CommandDistributor.h"
#include "WiThrottle.h"
#include "DCCTimer.h"
#if __has_include ( "MDNS_Generic.h")
#include "MDNS_Generic.h"
#define DO_MDNS
EthernetUDP udp;
MDNS mdns(udp);
#endif
bool EthernetInterface::connected=false;
EthernetServer * EthernetInterface::server= nullptr;
EthernetClient EthernetInterface::clients[MAX_SOCK_NUM]; // accept up to MAX_SOCK_NUM client connections at the same time; This depends on the chipset used on the Shield
uint8_t EthernetInterface::buffer[MAX_ETH_BUFFER+1]; // buffer used by TCP for the recv
RingStream * EthernetInterface::outboundRing = nullptr;
EthernetInterface * EthernetInterface::singleton=NULL;
/**
* @brief Setup Ethernet Connection
*
*/
void EthernetInterface::setup()
void EthernetInterface::setup() // STM32 VERSION
{
if (singleton!=NULL) {
DIAG(F("Prog Error!"));
return;
}
if ((singleton=new EthernetInterface()))
return;
DIAG(F("Ethernet not initialized"));
};
DIAG(F("Ethernet begin"
#ifdef DO_MDNS
" with mDNS"
#endif
));
#ifdef STM32_ETHERNET
// Set a HOSTNAME for the DHCP request - a nice to have, but hard it seems on LWIP for STM32
// The default is "lwip", which is **always** set in STM32Ethernet/src/utility/ethernetif.cpp
// for some reason. One can edit it to instead read:
// #if LWIP_NETIF_HOSTNAME
// /* Initialize interface hostname */
// if (netif->hostname == NULL)
// netif->hostname = "lwip";
// #endif /* LWIP_NETIF_HOSTNAME */
// Which seems more useful! We should propose the patch... so the following line actually works!
netif_set_hostname(&gnetif, WIFI_HOSTNAME); // Should probably be passed in the contructor...
#endif
#ifdef IP_ADDRESS
static IPAddress myIP(IP_ADDRESS);
#endif
/**
* @brief Aquire IP Address from DHCP and start server
*
* @return true
* @return false
*/
EthernetInterface::EthernetInterface()
{
byte mac[6];
DCCTimer::getSimulatedMacAddress(mac);
connected=false;
#ifdef IP_ADDRESS
Ethernet.begin(mac, myIP);
#else
if (Ethernet.begin(mac) == 0)
{
DIAG(F("Ethernet.begin FAILED"));
return;
}
#endif
if (Ethernet.hardwareStatus() == EthernetNoHardware) {
DIAG(F("Ethernet shield not found or W5100"));
}
unsigned long startmilli = millis();
while ((millis() - startmilli) < 5500) { // Loop to give time to check for cable connection
if (Ethernet.linkStatus() == LinkON)
break;
DIAG(F("Ethernet waiting for link (1sec) "));
delay(1000);
}
// now we either do have link of we have a W5100
// where we do not know if we have link. That's
// the reason to now run checkLink.
// CheckLinks sets up outboundRing if it does
// not exist yet as well.
checkLink();
#ifdef IP_ADDRESS
static IPAddress myIP(IP_ADDRESS);
Ethernet.begin(mac,myIP);
#else
if (Ethernet.begin(mac)==0)
{
LCD(4,F("IP: No DHCP"));
return;
}
#endif
auto ip = Ethernet.localIP(); // look what IP was obtained (dynamic or static)
if (!ip) {
LCD(4,F("IP: None"));
return;
}
server = new EthernetServer(IP_PORT); // Ethernet Server listening on default port IP_PORT
server->begin();
// Arrange display of IP address and port
#ifdef LCD_DRIVER
const byte lcdData[]={LCD_DRIVER};
const bool wideDisplay=lcdData[1]>=24; // data[1] is cols.
#else
const bool wideDisplay=true;
#endif
if (wideDisplay) {
// OLEDS or just usb diag is ok on one line.
LCD(4,F("IP %d.%d.%d.%d:%d"), ip[0], ip[1], ip[2], ip[3], IP_PORT);
}
else { // LCDs generally too narrow, so take 2 lines
LCD(4,F("IP %d.%d.%d.%d"), ip[0], ip[1], ip[2], ip[3]);
LCD(5,F("Port %d"), IP_PORT);
}
outboundRing=new RingStream(OUTBOUND_RING_SIZE);
#ifdef DO_MDNS
mdns.begin(Ethernet.localIP(), WIFI_HOSTNAME); // hostname
mdns.addServiceRecord(WIFI_HOSTNAME "._withrottle", IP_PORT, MDNSServiceTCP);
// Not sure if we need to run it once, but just in case!
mdns.run();
#endif
connected=true;
}
/**
* @brief Cleanup any resources
*
* @return none
*/
EthernetInterface::~EthernetInterface() {
delete server;
delete outboundRing;
}
/**
* @brief Main loop for the EthernetInterface
@ -107,134 +123,132 @@ EthernetInterface::~EthernetInterface() {
*/
void EthernetInterface::loop()
{
if (!singleton || (!singleton->checkLink()))
return;
if (!connected) return;
static bool warnedAboutLink=false;
if (Ethernet.linkStatus() == LinkOFF){
if (warnedAboutLink) return;
DIAG(F("Ethernet link OFF"));
warnedAboutLink=true;
return;
}
// link status must be ok here
if (warnedAboutLink) {
DIAG(F("Ethernet link RESTORED"));
warnedAboutLink=false;
}
#ifdef DO_MDNS
// Always do this because we don't want traffic to intefere with being found!
mdns.run();
#endif
//
switch (Ethernet.maintain()) {
case 1:
//renewed fail
DIAG(F("Ethernet Error: renewed fail"));
singleton=NULL;
connected=false;
return;
case 3:
//rebind fail
DIAG(F("Ethernet Error: rebind fail"));
singleton=NULL;
connected=false;
return;
default:
//nothing happened
//DIAG(F("maintained"));
break;
}
singleton->loop2();
}
/**
* @brief Checks ethernet link cable status and detects when it connects / disconnects
*
* @return true when cable is connected, false otherwise
*/
bool EthernetInterface::checkLink() {
if (Ethernet.linkStatus() != LinkOFF) { // check for not linkOFF instead of linkON as the W5100 does return LinkUnknown
//if we are not connected yet, setup a new server
if(!connected) {
DIAG(F("Ethernet cable connected"));
connected=true;
#ifdef IP_ADDRESS
Ethernet.setLocalIP(myIP); // for static IP, set it again
#endif
IPAddress ip = Ethernet.localIP(); // look what IP was obtained (dynamic or static)
server = new EthernetServer(IP_PORT); // Ethernet Server listening on default port IP_PORT
server->begin();
LCD(4,F("IP: %d.%d.%d.%d"), ip[0], ip[1], ip[2], ip[3]);
LCD(5,F("Port:%d"), IP_PORT);
// only create a outboundRing it none exists, this may happen if the cable
// gets disconnected and connected again
if(!outboundRing)
outboundRing=new RingStream(OUTBOUND_RING_SIZE);
}
return true;
} else { // connected
DIAG(F("Ethernet cable disconnected"));
connected=false;
//clean up any client
for (byte socket = 0; socket < MAX_SOCK_NUM; socket++) {
if(clients[socket].connected())
clients[socket].stop();
}
// tear down server
delete server;
server = nullptr;
LCD(4,F("IP: None"));
}
return false;
}
void EthernetInterface::loop2() {
if (!outboundRing) { // no idea to call loop2() if we can't handle outgoing data in it
if (Diag::ETHERNET) DIAG(F("No outboundRing"));
return;
}
// get client from the server
EthernetClient client = server->accept();
// check for new client
if (client)
{
if (Diag::ETHERNET) DIAG(F("Ethernet: New client "));
byte socket;
// get client from the server
#if defined (STM32_ETHERNET)
// STM32Ethernet doesn't use accept(), just available()
auto client = server->available();
if (client) {
// check for new client
byte socket;
bool sockfound = false;
for (socket = 0; socket < MAX_SOCK_NUM; socket++)
{
if (client == clients[socket])
{
sockfound = true;
break;
}
}
if (!sockfound)
{ // new client
for (socket = 0; socket < MAX_SOCK_NUM; socket++)
{
if (!clients[socket])
{
// On accept() the EthernetServer doesn't track the client anymore
// so we store it in our client array
if (Diag::ETHERNET) DIAG(F("Socket %d"),socket);
clients[socket] = client;
break;
}
if (!clients[socket])
{
clients[socket] = client;
sockfound=true;
if (Diag::ETHERNET)
DIAG(F("Ethernet: New client socket %d"), socket);
break;
}
}
if (socket==MAX_SOCK_NUM) DIAG(F("new Ethernet OVERFLOW"));
}
if (!sockfound) DIAG(F("new Ethernet OVERFLOW"));
}
#else
auto client = server->accept();
if (client) clients[client.getSocketNumber()]=client;
#endif
// check for incoming data from all possible clients
for (byte socket = 0; socket < MAX_SOCK_NUM; socket++)
{
if (clients[socket]) {
int available=clients[socket].available();
if (available > 0) {
if (Diag::ETHERNET) DIAG(F("Ethernet: available socket=%d,avail=%d"), socket, available);
// read bytes from a client
int count = clients[socket].read(buffer, MAX_ETH_BUFFER);
buffer[count] = '\0'; // terminate the string properly
if (Diag::ETHERNET) DIAG(F(",count=%d:%e"), socket,buffer);
// execute with data going directly back
CommandDistributor::parse(socket,buffer,outboundRing);
return; // limit the amount of processing that takes place within 1 loop() cycle.
}
}
}
// stop any clients which disconnect
for (int socket = 0; socket<MAX_SOCK_NUM; socket++) {
if (clients[socket] && !clients[socket].connected()) {
clients[socket].stop();
CommandDistributor::forget(socket);
if (Diag::ETHERNET) DIAG(F("Ethernet: disconnect %d "), socket);
}
}
if (!clients[socket]) continue; // socket is not in use
// read any bytes from this client
auto count = clients[socket].read(buffer, MAX_ETH_BUFFER);
if (count<0) continue; // -1 indicates nothing to read
if (count > 0) { // we have incoming data
buffer[count] = '\0'; // terminate the string properly
if (Diag::ETHERNET) DIAG(F("Ethernet s=%d, c=%d b=:%e"), socket, count, buffer);
// execute with data going directly back
CommandDistributor::parse(socket,buffer,outboundRing);
return; // limit the amount of processing that takes place within 1 loop() cycle.
}
// count=0 The client has disconnected
clients[socket].stop();
CommandDistributor::forget(socket);
if (Diag::ETHERNET) DIAG(F("Ethernet: disconnect %d "), socket);
}
WiThrottle::loop(outboundRing);
// handle at most 1 outbound transmission
int socketOut=outboundRing->read();
auto socketOut=outboundRing->read();
if (socketOut<0) return; // no outbound pending
if (socketOut >= MAX_SOCK_NUM) {
DIAG(F("Ethernet outboundRing socket=%d error"), socketOut);
} else if (socketOut >= 0) {
int count=outboundRing->count();
if (Diag::ETHERNET) DIAG(F("Ethernet reply socket=%d, count=:%d"), socketOut,count);
for(;count>0;count--) clients[socketOut].write(outboundRing->read());
clients[socketOut].flush(); //maybe
// This is a catastrophic code failure and unrecoverable.
DIAG(F("Ethernet outboundRing s=%d error"), socketOut);
connected=false;
return;
}
auto count=outboundRing->count();
{
char tmpbuf[count+1]; // one extra for '\0'
for(int i=0;i<count;i++) {
tmpbuf[i] = outboundRing->read();
}
tmpbuf[count]=0;
if (Diag::ETHERNET) DIAG(F("Ethernet reply s=%d, c=%d, b:%e"),
socketOut,count,tmpbuf);
clients[socketOut].write(tmpbuf,count);
}
}
#endif

View File

@ -35,6 +35,14 @@
#if defined (ARDUINO_TEENSY41)
#include <NativeEthernet.h> //TEENSY Ethernet Treiber
#include <NativeEthernetUdp.h>
#elif defined (ARDUINO_NUCLEO_F429ZI) || defined (ARDUINO_NUCLEO_F439ZI) || defined (ARDUINO_NUCLEO_F4X9ZI)
#include <LwIP.h>
// #include "STM32lwipopts.h"
#include <STM32Ethernet.h>
#include <lwip/netif.h>
extern "C" struct netif gnetif;
#define STM32_ETHERNET
#define MAX_SOCK_NUM 8
#else
#include "Ethernet.h"
#endif
@ -45,7 +53,7 @@
*
*/
#define MAX_ETH_BUFFER 512
#define MAX_ETH_BUFFER 128
#define OUTBOUND_RING_SIZE 2048
class EthernetInterface {
@ -56,16 +64,11 @@ class EthernetInterface {
static void loop();
private:
static EthernetInterface * singleton;
bool connected;
EthernetInterface();
~EthernetInterface();
void loop2();
bool checkLink();
EthernetServer * server = NULL;
EthernetClient clients[MAX_SOCK_NUM]; // accept up to MAX_SOCK_NUM client connections at the same time; This depends on the chipset used on the Shield
uint8_t buffer[MAX_ETH_BUFFER+1]; // buffer used by TCP for the recv
RingStream * outboundRing = NULL;
static bool connected;
static EthernetServer * server;
static EthernetClient clients[MAX_SOCK_NUM]; // accept up to MAX_SOCK_NUM client connections at the same time; This depends on the chipset used on the Shield
static uint8_t buffer[MAX_ETH_BUFFER+1]; // buffer used by TCP for the recv
static RingStream * outboundRing;
};
#endif

8
FSH.h
View File

@ -52,6 +52,7 @@ typedef __FlashStringHelper FSH;
#define STRNCPY_P strncpy_P
#define STRNCMP_P strncmp_P
#define STRLEN_P strlen_P
#define STRCHR_P strchr_P
#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)
// AVR_MEGA memory deliberately placed at end of link may need _far functions
@ -60,6 +61,8 @@ typedef __FlashStringHelper FSH;
#define GETFARPTR(data) pgm_get_far_address(data)
#define GETHIGHFLASH(data,offset) pgm_read_byte_far(GETFARPTR(data)+offset)
#define GETHIGHFLASHW(data,offset) pgm_read_word_far(GETFARPTR(data)+offset)
#define COPYHIGHFLASH(target,base,offset,length) \
memcpy_PF(target,GETFARPTR(base) + offset,length)
#else
// AVR_UNO/NANO runtime does not support _far functions so just use _near equivalent
// as there is no progmem above 32kb anyway.
@ -68,6 +71,8 @@ typedef __FlashStringHelper FSH;
#define GETFARPTR(data) ((uint32_t)(data))
#define GETHIGHFLASH(data,offset) pgm_read_byte_near(GETFARPTR(data)+(offset))
#define GETHIGHFLASHW(data,offset) pgm_read_word_near(GETFARPTR(data)+(offset))
#define COPYHIGHFLASH(target,base,offset,length) \
memcpy_P(target,(byte *)base + offset,length)
#endif
#else
@ -87,10 +92,13 @@ typedef char FSH;
#define GETFLASH(addr) (*(const byte *)(addr))
#define GETHIGHFLASH(data,offset) (*(const byte *)(GETFARPTR(data)+offset))
#define GETHIGHFLASHW(data,offset) (*(const uint16_t *)(GETFARPTR(data)+offset))
#define COPYHIGHFLASH(target,base,offset,length) \
memcpy(target,(byte *)&base + offset,length)
#define STRCPY_P strcpy
#define STRCMP_P strcmp
#define STRNCPY_P strncpy
#define STRNCMP_P strncmp
#define STRLEN_P strlen
#define STRCHR_P strchr
#endif
#endif

View File

@ -1 +1 @@
#define GITHUB_SHA "devel-202408080849Z"
#define GITHUB_SHA "devel-202409221903Z"

View File

@ -46,27 +46,37 @@
// Helper function for listing device types
static const FSH * guessI2CDeviceType(uint8_t address) {
if (address == 0x1A)
// 0x09-0x18 selectable, but for now handle the default
return F("Piicodev 865/915MHz Transceiver");
if (address == 0x1C)
return F("QMC6310 Magnetometer");
if (address >= 0x20 && address <= 0x26)
return F("GPIO Expander");
else if (address == 0x27)
if (address == 0x27)
return F("GPIO Expander or LCD Display");
else if (address == 0x29)
if (address == 0x29)
return F("Time-of-flight sensor");
else if (address >= 0x3c && address <= 0x3d)
return F("OLED Display");
else if (address >= 0x48 && address <= 0x57) // SC16IS752x UART detection
if (address == 0x34)
return F("TCA8418 keypad scanner");
if (address >= 0x3c && address <= 0x3d)
// 0x3c can also be an HMC883L magnetometer
return F("OLED Display or HMC583L Magnetometer");
if (address >= 0x48 && address <= 0x57) // SC16IS752x UART detection
return F("SC16IS75x UART");
else if (address >= 0x48 && address <= 0x4f)
if (address >= 0x48 && address <= 0x4f)
return F("Analogue Inputs or PWM");
else if (address >= 0x40 && address <= 0x4f)
if (address >= 0x40 && address <= 0x4f)
return F("PWM");
else if (address >= 0x50 && address <= 0x5f)
if (address >= 0x50 && address <= 0x5f)
return F("EEPROM");
else if (address == 0x68)
if (address >= 0x60 && address <= 0x68)
return F("Adafruit NeoPixel Driver");
if (address == 0x68)
return F("Real-time clock");
else if (address >= 0x70 && address <= 0x77)
if (address >= 0x70 && address <= 0x77)
return F("I2C Mux");
else
// Unknown type
return F("?");
}

View File

@ -251,6 +251,26 @@ void IODevice::write(VPIN vpin, int value) {
#endif
}
// Write value to count virtual pin(s).
// these may be within one driver or separated over several drivers
void IODevice::writeRange(VPIN vpin, int value, int count) {
while(count) {
auto dev = findDevice(vpin);
if (dev) {
auto vpinBefore=vpin;
// write to driver, driver will return next vpin it cant handle
vpin=dev->_writeRange(vpin, value,count);
count-= vpin-vpinBefore; // decrement by number of vpins changed
}
else {
// skip a vpin if no device handler
vpin++;
count--;
}
}
}
// Write analogue value to virtual pin(s). If multiple devices are allocated
// the same pin then only the first one found will be used.
//
@ -270,6 +290,24 @@ void IODevice::writeAnalogue(VPIN vpin, int value, uint8_t param1, uint16_t para
#endif
}
//
void IODevice::writeAnalogueRange(VPIN vpin, int value, uint8_t param1, uint16_t param2,int count) {
while(count) {
auto dev = findDevice(vpin);
if (dev) {
auto vpinBefore=vpin;
// write to driver, driver will return next vpin it cant handle
vpin=dev->_writeAnalogueRange(vpin, value, param1, param2,count);
count-= vpin-vpinBefore; // decrement by number of vpins changed
}
else {
// skip a vpin if no device handler
vpin++;
count--;
}
}
}
// isBusy, when called for a device pin is always a digital output or analogue output,
// returns input feedback state of the pin, i.e. whether the pin is busy performing
// an animation or fade over a period of time.

View File

@ -128,9 +128,11 @@ public:
// write invokes the IODevice instance's _write method.
static void write(VPIN vpin, int value);
static void writeRange(VPIN vpin, int value,int count);
// write invokes the IODevice instance's _writeAnalogue method (not applicable for digital outputs)
static void writeAnalogue(VPIN vpin, int value, uint8_t profile=0, uint16_t duration=0);
static void writeAnalogueRange(VPIN vpin, int value, uint8_t profile, uint16_t duration, int count);
// isBusy returns true if the device is currently in an animation of some sort, e.g. is changing
// the output over a period of time.
@ -177,11 +179,29 @@ public:
virtual void _write(VPIN vpin, int value) {
(void)vpin; (void)value;
};
// Method to write new state (optionally implemented within device class)
// This will, by default just write to one vpin and return whet to do next.
// the real power comes where a single driver can update many vpins in one call.
virtual VPIN _writeRange(VPIN vpin, int value, int count) {
(void)count;
_write(vpin,value);
return vpin+1; // try next vpin
};
// Method to write an 'analogue' value (optionally implemented within device class)
virtual void _writeAnalogue(VPIN vpin, int value, uint8_t param1=0, uint16_t param2=0) {
(void)vpin; (void)value; (void) param1; (void)param2;
};
// Method to write an 'analogue' value to a VPIN range (optionally implemented within device class)
// This will, by default just write to one vpin and return whet to do next.
// the real power comes where a single driver can update many vpins in one call.
virtual VPIN _writeAnalogueRange(VPIN vpin, int value, uint8_t param1, uint16_t param2, int count) {
(void) count;
_writeAnalogue(vpin, value, param1, param2);
return vpin+1;
};
// Method to read digital pin state (optionally implemented within device class)
virtual int _read(VPIN vpin) {
@ -548,5 +568,8 @@ protected:
#include "IO_EXIOExpander.h"
#include "IO_trainbrains.h"
#include "IO_EncoderThrottle.h"
#include "IO_TCA8418.h"
#include "IO_NeoPixel.h"
#endif // iodevice_h

333
IO_NeoPixel.h Normal file
View File

@ -0,0 +1,333 @@
/*
* © 2024, Chris Harlow. All rights reserved.
*
* This file is part of EX-CommandStation
*
* 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/>.
*/
/*
* The IO_NEOPIXEL.h device driver integrates with one or more Adafruit neopixel drivers.
* This device driver will configure the device on startup, along with
* interacting with the device for all input/output duties.
*
* To create NEOPIXEL devices, these are defined in myAutomation.h:
* (Note the device driver is included by default)
*
* HAL(NEOPIXEL,first vpin, number of pixels,mode, i2c address)
* e.g. HAL(NEOPIXEL,1000,64,NEO_RGB,0x60)
* This gives each pixel in the chain an individual vpin
* The number of pixels must match the physical pixels in the chain.
*
* This driver maintains a colour (rgb value in 5,5,5 bits only) plus an ON bit.
* This can be written/read with an analog write/read call.
* The ON bit can be set on and off with a digital write. This allows for
* a pixel to be preset a colour and then turned on and off like any other light.
*/
#ifndef IO_EX_NeoPixel_H
#define IO_EX_NeoPixel_H
#include "IODevice.h"
#include "I2CManager.h"
#include "DIAG.h"
#include "FSH.h"
// The following macros to define the Neopixel String type
// have been copied from the Adafruit Seesaw Library under the
// terms of the GPL.
// Credit to: https://github.com/adafruit/Adafruit_Seesaw
// The order of primary colors in the NeoPixel data stream can vary
// among device types, manufacturers and even different revisions of
// the same item. The third parameter to the seesaw_NeoPixel
// constructor encodes the per-pixel byte offsets of the red, green
// and blue primaries (plus white, if present) in the data stream --
// the following #defines provide an easier-to-use named version for
// each permutation. e.g. NEO_GRB indicates a NeoPixel-compatible
// device expecting three bytes per pixel, with the first byte
// containing the green value, second containing red and third
// containing blue. The in-memory representation of a chain of
// NeoPixels is the same as the data-stream order; no re-ordering of
// bytes is required when issuing data to the chain.
// Bits 5,4 of this value are the offset (0-3) from the first byte of
// a pixel to the location of the red color byte. Bits 3,2 are the
// green offset and 1,0 are the blue offset. If it is an RGBW-type
// device (supporting a white primary in addition to R,G,B), bits 7,6
// are the offset to the white byte...otherwise, bits 7,6 are set to
// the same value as 5,4 (red) to indicate an RGB (not RGBW) device.
// i.e. binary representation:
// 0bWWRRGGBB for RGBW devices
// 0bRRRRGGBB for RGB
// RGB NeoPixel permutations; white and red offsets are always same
// Offset: W R G B
#define NEO_RGB ((0 << 6) | (0 << 4) | (1 << 2) | (2))
#define NEO_RBG ((0 << 6) | (0 << 4) | (2 << 2) | (1))
#define NEO_GRB ((1 << 6) | (1 << 4) | (0 << 2) | (2))
#define NEO_GBR ((2 << 6) | (2 << 4) | (0 << 2) | (1))
#define NEO_BRG ((1 << 6) | (1 << 4) | (2 << 2) | (0))
#define NEO_BGR ((2 << 6) | (2 << 4) | (1 << 2) | (0))
// RGBW NeoPixel permutations; all 4 offsets are distinct
// Offset: W R G B
#define NEO_WRGB ((0 << 6) | (1 << 4) | (2 << 2) | (3))
#define NEO_WRBG ((0 << 6) | (1 << 4) | (3 << 2) | (2))
#define NEO_WGRB ((0 << 6) | (2 << 4) | (1 << 2) | (3))
#define NEO_WGBR ((0 << 6) | (3 << 4) | (1 << 2) | (2))
#define NEO_WBRG ((0 << 6) | (2 << 4) | (3 << 2) | (1))
#define NEO_WBGR ((0 << 6) | (3 << 4) | (2 << 2) | (1))
#define NEO_RWGB ((1 << 6) | (0 << 4) | (2 << 2) | (3))
#define NEO_RWBG ((1 << 6) | (0 << 4) | (3 << 2) | (2))
#define NEO_RGWB ((2 << 6) | (0 << 4) | (1 << 2) | (3))
#define NEO_RGBW ((3 << 6) | (0 << 4) | (1 << 2) | (2))
#define NEO_RBWG ((2 << 6) | (0 << 4) | (3 << 2) | (1))
#define NEO_RBGW ((3 << 6) | (0 << 4) | (2 << 2) | (1))
#define NEO_GWRB ((1 << 6) | (2 << 4) | (0 << 2) | (3))
#define NEO_GWBR ((1 << 6) | (3 << 4) | (0 << 2) | (2))
#define NEO_GRWB ((2 << 6) | (1 << 4) | (0 << 2) | (3))
#define NEO_GRBW ((3 << 6) | (1 << 4) | (0 << 2) | (2))
#define NEO_GBWR ((2 << 6) | (3 << 4) | (0 << 2) | (1))
#define NEO_GBRW ((3 << 6) | (2 << 4) | (0 << 2) | (1))
#define NEO_BWRG ((1 << 6) | (2 << 4) | (3 << 2) | (0))
#define NEO_BWGR ((1 << 6) | (3 << 4) | (2 << 2) | (0))
#define NEO_BRWG ((2 << 6) | (1 << 4) | (3 << 2) | (0))
#define NEO_BRGW ((3 << 6) | (1 << 4) | (2 << 2) | (0))
#define NEO_BGWR ((2 << 6) | (3 << 4) | (1 << 2) | (0))
#define NEO_BGRW ((3 << 6) | (2 << 4) | (1 << 2) | (0))
// If 400 KHz support is enabled, the third parameter to the constructor
// requires a 16-bit value (in order to select 400 vs 800 KHz speed).
// If only 800 KHz is enabled (as is default on ATtiny), an 8-bit value
// is sufficient to encode pixel color order, saving some space.
#define NEO_KHZ800 0x0000 // 800 KHz datastream
#define NEO_KHZ400 0x0100 // 400 KHz datastream
/////////////////////////////////////////////////////////////////////////////////////////////////////
/*
* IODevice subclass for NeoPixel.
*/
class NeoPixel : public IODevice {
public:
static void create(VPIN vpin, int nPins, uint16_t mode=(NEO_GRB | NEO_KHZ800), I2CAddress i2cAddress=0x60) {
if (checkNoOverlap(vpin, nPins, mode, i2cAddress)) new NeoPixel(vpin, nPins, mode, i2cAddress);
}
private:
static const byte SEESAW_NEOPIXEL_BASE=0x0E;
static const byte SEESAW_NEOPIXEL_STATUS = 0x00;
static const byte SEESAW_NEOPIXEL_PIN = 0x01;
static const byte SEESAW_NEOPIXEL_SPEED = 0x02;
static const byte SEESAW_NEOPIXEL_BUF_LENGTH = 0x03;
static const byte SEESAW_NEOPIXEL_BUF=0x04;
static const byte SEESAW_NEOPIXEL_SHOW=0x05;
// all adafruit examples say this pin. Presumably its hard wired
// in the adapter anyway.
static const byte SEESAW_PIN15 = 15;
// Constructor
NeoPixel(VPIN firstVpin, int nPins, uint16_t mode, I2CAddress i2cAddress) {
_firstVpin = firstVpin;
_nPins=nPins;
_I2CAddress = i2cAddress;
// calculate the offsets into the seesaw buffer for each colour depending
// on the pixel strip type passed in mode.
_redOffset=4+(mode >> 4 & 0x03);
_greenOffset=4+(mode >> 2 & 0x03);
_blueOffset=4+(mode & 0x03);
if (4+(mode >>6 & 0x03) == _redOffset) _bytesPerPixel=3;
else _bytesPerPixel=4; // string has a white byte.
_kHz800=(mode & NEO_KHZ400)==0;
_showPendimg=false;
// Each pixel requires 3 bytes RGB memory.
// Although the driver device can remember this, it cant do off/on without
// forgetting what the on colour was!
pixelBuffer=(RGB *) malloc(_nPins*sizeof(RGB));
stateBuffer=(byte *) calloc((_nPins+7)/8,sizeof(byte)); // all pixels off
if (pixelBuffer==nullptr || stateBuffer==nullptr) {
DIAG(F("NeoPixel I2C:%s not enough RAM"), _I2CAddress.toString());
return;
}
// preset all pins to white so a digital on/off will do something even if no colour set.
memset(pixelBuffer,0xFF,_nPins*sizeof(RGB));
addDevice(this);
}
void _begin() {
// Initialise Neopixel device
I2CManager.begin();
if (!I2CManager.exists(_I2CAddress)) {
DIAG(F("NeoPixel I2C:%s device not found"), _I2CAddress.toString());
_deviceState = DEVSTATE_FAILED;
return;
}
byte speedBuffer[]={SEESAW_NEOPIXEL_BASE, SEESAW_NEOPIXEL_SPEED,_kHz800};
I2CManager.write(_I2CAddress, speedBuffer, sizeof(speedBuffer));
// In the driver there are 3 of 4 byts per pixel
auto numBytes=_bytesPerPixel * _nPins;
byte setbuffer[] = {SEESAW_NEOPIXEL_BASE, SEESAW_NEOPIXEL_BUF_LENGTH,
(byte)(numBytes >> 8), (byte)(numBytes & 0xFF)};
I2CManager.write(_I2CAddress, setbuffer, sizeof(setbuffer));
const byte pinbuffer[] = {SEESAW_NEOPIXEL_BASE, SEESAW_NEOPIXEL_PIN,SEESAW_PIN15};
I2CManager.write(_I2CAddress, pinbuffer, sizeof(pinbuffer));
for (auto pin=0;pin<_nPins;pin++) transmit(pin);
_display();
}
// loop called by HAL supervisor
void _loop(unsigned long currentMicros) override {
if (!_showPendimg) return;
byte showBuffer[]={SEESAW_NEOPIXEL_BASE,SEESAW_NEOPIXEL_SHOW};
I2CManager.write(_I2CAddress,showBuffer,sizeof(showBuffer));
_showPendimg=false;
}
// read back pixel on/off
int _read(VPIN vpin) override {
if (_deviceState == DEVSTATE_FAILED) return 0;
return isPixelOn(vpin-_firstVpin);
}
// Write digital value. Sets pixel on or off
void _write(VPIN vpin, int value) override {
if (_deviceState == DEVSTATE_FAILED) return;
auto pixel=vpin-_firstVpin;
if (value) {
if (isPixelOn(pixel)) return;
setPixelOn(pixel);
}
else { // set off
if (!isPixelOn(pixel)) return;
setPixelOff(pixel);
}
transmit(pixel);
}
VPIN _writeRange(VPIN vpin,int value, int count) {
// using write range cuts out the constant vpin to driver lookup so
// we can update multiple pixels much faster.
VPIN nextVpin=vpin + (count>_nPins ? _nPins : count);
if (_deviceState != DEVSTATE_FAILED) while(vpin<nextVpin) {
_write(vpin,value);
vpin++;
}
return nextVpin; // next pin we cant
}
// Write analogue value.
// The convoluted parameter mashing here is to allow passing the RGB and on/off
// information through the generic HAL _writeAnalog interface which was originally
// designed for servos and short integers
void _writeAnalogue(VPIN vpin, int colour_RG, uint8_t onoff, uint16_t colour_B) override {
if (_deviceState == DEVSTATE_FAILED) return;
RGB newColour={(byte)((colour_RG>>8) & 0xFF), (byte)(colour_RG & 0xFF), (byte)(colour_B & 0xFF)};
auto pixel=vpin-_firstVpin;
if (pixelBuffer[pixel]==newColour && isPixelOn(pixel)==(bool)onoff) return; // no change
if (onoff) setPixelOn(pixel); else setPixelOff(pixel);
pixelBuffer[pixel]=newColour;
transmit(pixel);
}
VPIN _writeAnalogueRange(VPIN vpin, int colour_RG, uint8_t onoff, uint16_t colour_B, int count) override {
// using write range cuts out the constant vpin to driver lookup so
VPIN nextVpin=vpin + (count>_nPins ? _nPins : count);
if (_deviceState != DEVSTATE_FAILED) while(vpin<nextVpin) {
_writeAnalogue(vpin,colour_RG, onoff,colour_B);
vpin++;
}
return nextVpin; // next pin we cant
}
// Display device information and status.
void _display() override {
DIAG(F("NeoPixel I2C:%s Vpins %u-%u %S"),
_I2CAddress.toString(),
(int)_firstVpin, (int)_firstVpin+_nPins-1,
_deviceState == DEVSTATE_FAILED ? F("OFFLINE") : F(""));
}
bool isPixelOn(int16_t pixel) {return stateBuffer[pixel/8] & (0x80>>(pixel%8));}
void setPixelOn(int16_t pixel) {stateBuffer[pixel/8] |= (0x80>>(pixel%8));}
void setPixelOff(int16_t pixel) {stateBuffer[pixel/8] &= ~(0x80>>(pixel%8));}
// Helper function for error handling
void reportError(uint8_t status, bool fail=true) {
DIAG(F("NeoPixel I2C:%s Error:%d (%S)"), _I2CAddress.toString(),
status, I2CManager.getErrorMessage(status));
if (fail)
_deviceState = DEVSTATE_FAILED;
}
void transmit(uint16_t pixel, bool show=true) {
byte buffer[]={SEESAW_NEOPIXEL_BASE,SEESAW_NEOPIXEL_BUF,0x00,0x00,0x00,0x00,0x00};
uint16_t offset= pixel * _bytesPerPixel;
buffer[2]=(byte)(offset>>8);
buffer[3]=(byte)(offset & 0xFF);
if (isPixelOn(pixel)) {
auto colour=pixelBuffer[pixel];
buffer[_redOffset]=colour.red;
buffer[_greenOffset]=colour.green;
buffer[_blueOffset]=colour.blue;
} // else leave buffer black (in buffer preset to zeros above)
// Transmit pixel to driver
I2CManager.write(_I2CAddress,buffer,4 +_bytesPerPixel);
_showPendimg=true;
}
struct RGB {
byte red;
byte green;
byte blue;
bool operator==(const RGB& other) const {
return red == other.red && green == other.green && blue == other.blue;
}
};
RGB* pixelBuffer = nullptr;
byte* stateBuffer = nullptr; // 1 bit per pixel
bool _showPendimg;
// mapping of RGB onto pixel buffer for seesaw.
byte _bytesPerPixel;
byte _redOffset;
byte _greenOffset;
byte _blueOffset;
bool _kHz800;
};
#endif

184
IO_TCA8418.h Normal file
View File

@ -0,0 +1,184 @@
/*
* © 2023, Paul M. Antoine
* © 2021, 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/>.
*/
#ifndef io_tca8418_h
#define io_tca8418_h
#include "IO_GPIOBase.h"
#include "FSH.h"
/////////////////////////////////////////////////////////////////////////////////////////////////////
/*
* IODevice subclass for TCA8418 80-key keypad encoder, which we'll treat as 64 of the possible
* 80 inputs for now, in an 8x8 matrix only, although the datasheet says:
*
* The TCA8418 can be configured to support many different configurations of keypad setups.
* All 18 GPIOs for the rows and columns can be used to support up to 80 keys in an 8x10 key pad
* array. Another option is that all 18 GPIOs be used for GPIs to read 18 buttons which are
* not connected in an array. Any combination in between is also acceptable (for example, a
* 3x4 keypad matrix and using the remaining 11 GPIOs as a combination of inputs and outputs).
*/
class TCA8418 : public GPIOBase<uint64_t> {
public:
static void create(VPIN vpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin=-1) {
if (checkNoOverlap(vpin, nPins, i2cAddress))
// temporarily use the simple 18-pin GPIO mode - we'll switch to 8x8 matrix once this works
new TCA8418(vpin, (nPins = (nPins > 18) ? 18 : nPins), i2cAddress, interruptPin);
}
private:
// Constructor
TCA8418(VPIN vpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin=-1)
: GPIOBase<uint64_t>((FSH *)F("TCA8418"), vpin, nPins, i2cAddress, interruptPin)
{
uint8_t receiveBuffer[1];
uint8_t commandBuffer[1];
uint8_t status;
commandBuffer[0] = REG_INT_STAT; // Check interrupt status
status = I2CManager.read(_I2CAddress, receiveBuffer, sizeof(receiveBuffer), commandBuffer, sizeof(commandBuffer));
if (status == I2C_STATUS_OK) {
DIAG(F("TCA8418 Interrupt status was: %x"), receiveBuffer[0]);
}
else
DIAG(F("TCA8418 Interrupt status failed to read!"));
// requestBlock.setRequestParams(_I2CAddress, inputBuffer, sizeof(inputBuffer),
// outputBuffer, sizeof(outputBuffer));
// outputBuffer[0] = REG_GPIOA;
}
void _writeGpioPort() override {
// I2CManager.write(_I2CAddress, 3, REG_GPIOA, _portOutputState, _portOutputState>>8);
}
void _writePullups() override {
// Set pullups only for in-use pins. This prevents pullup being set for a pin that
// is intended for use as an output but hasn't been written to yet.
uint32_t temp = _portPullup & _portInUse;
(void)temp; // Chris did this so he could see warnings that mattered
// I2CManager.write(_I2CAddress, 3, REG_GPPUA, temp, temp>>8);
}
void _writePortModes() override {
// Write 0 to each GPIO_DIRn for in-use pins that are inputs, 1 for outputs
uint64_t temp = _portMode & _portInUse;
DIAG(F("TCA8418 writing Port Mode: %x, to GPIO_DIRs"), temp);
DIAG(F("TCA8418 writing Port Mode: %x, to GPIO_DIR1"), (temp&0xFF));
I2CManager.write(_I2CAddress, 2, REG_GPIO_DIR1, (temp&0xFF));
DIAG(F("TCA8418 writing Port Mode: %x, to GPIO_DIR2"), ((temp&0xFF00)>>8));
I2CManager.write(_I2CAddress, 2, REG_GPIO_DIR2, ((temp&0xFF00)>>8));
DIAG(F("TCA8418 writing Port Mode: %x, to GPIO_DIR3"), (temp&0x30000)>>16);
I2CManager.write(_I2CAddress, 2, REG_GPIO_DIR3, ((temp&0x30000)>>16));
// Enable interrupt for in-use pins which are inputs (_portMode=0)
// TCA8418 has interrupt enables per pin, but must be configured for low->high
// or high->low... unlike the MCP23017
temp = ~_portMode & _portInUse;
DIAG(F("TCA8418 writing interrupt Port Mode: %x, to GPIO_INT_ENs"), temp);
DIAG(F("TCA8418 writing interrupt Port Mode: %x, to GPIO_INT_EN1"), (temp&0xFF));
I2CManager.write(_I2CAddress, 2, REG_GPIO_INT_EN1, (temp&0xFF));
DIAG(F("TCA8418 writing interrupt Port Mode: %x, to GPIO_INT_EN2"), ((temp&0xFF00)>>8));
I2CManager.write(_I2CAddress, 2, REG_GPIO_INT_EN2, ((temp&0xFF00)>>8));
DIAG(F("TCA8418 writing interrupt Port Mode: %x, to GPIO_INT_EN3"), (temp&0x30000)>>16);
I2CManager.write(_I2CAddress, 2, REG_GPIO_INT_EN3, ((temp&0x30000)>>16));
// I2CManager.write(_I2CAddress, 3, REG_INTCONA, 0x00, 0x00);
// I2CManager.write(_I2CAddress, 3, REG_GPINTENA, temp, temp>>8);
}
void _readGpioPort(bool immediate) override {
// if (immediate) {
// uint8_t buffer[2];
// I2CManager.read(_I2CAddress, buffer, 2, 1, REG_GPIOA);
// _portInputState = ((uint16_t)buffer[1]<<8) | buffer[0] | _portMode;
// } else {
// // Queue new request
// requestBlock.wait(); // Wait for preceding operation to complete
// // Issue new request to read GPIO register
// I2CManager.queueRequest(&requestBlock);
// }
}
// This function is invoked when an I/O operation on the requestBlock completes.
void _processCompletion(uint8_t status) override {
// if (status == I2C_STATUS_OK)
// _portInputState = (((uint16_t)inputBuffer[1]<<8) | inputBuffer[0]) | _portMode;
// else
// _portInputState = 0xffff;
}
void _setupDevice() override {
DIAG(F("TCA8418 setupDevice() called"));
// IOCON is set MIRROR=1, ODR=1 (open drain shared interrupt pin)
// I2CManager.write(_I2CAddress, 2, REG_IOCON, 0x44);
_writePortModes();
_writePullups();
_writeGpioPort();
}
enum
{
REG_FIRST_RESERVED = 0x00,
REG_CFG = 0x01,
REG_INT_STAT = 0x02,
REG_KEY_LCK_EC = 0x03,
REG_KEY_EVENT_A = 0x04,
REG_KEY_EVENT_B = 0x05,
REG_KEY_EVENT_C = 0x06,
REG_KEY_EVENT_D = 0x07,
REG_KEY_EVENT_E = 0x08,
REG_KEY_EVENT_F = 0x09,
REG_KEY_EVENT_G = 0x0A,
REG_KEY_EVENT_H = 0x0B,
REG_KEY_EVENT_I = 0x0C,
REG_KEY_EVENT_J = 0x0D,
REG_KP_LCK_TIMER = 0x0E,
REG_UNLOCK1 = 0x0F,
REG_UNLOCK2 = 0x10,
REG_GPIO_INT_STAT1 = 0x11,
REG_GPIO_INT_STAT2 = 0x12,
REG_GPIO_INT_STAT3 = 0x13,
REG_GPIO_DAT_STAT1 = 0x14,
REG_GPIO_DAT_STAT2 = 0x15,
REG_GPIO_DAT_STAT3 = 0x16,
REG_GPIO_DAT_OUT1 = 0x17,
REG_GPIO_DAT_OUT2 = 0x18,
REG_GPIO_DAT_OUT3 = 0x19,
REG_GPIO_INT_EN1 = 0x1A,
REG_GPIO_INT_EN2 = 0x1B,
REG_GPIO_INT_EN3 = 0x1C,
REG_KP_GPIO1 = 0x1D,
REG_KP_GPIO2 = 0x1E,
REG_KP_GPIO3 = 0x1F,
REG_GPI_EM1 = 0x20,
REG_GPI_EM2 = 0x21,
REG_GPI_EM3 = 0x22,
REG_GPIO_DIR1 = 0x23,
REG_GPIO_DIR2 = 0x24,
REG_GPIO_DIR3 = 0x25,
REG_GPIO_INT_LVL1 = 0x26,
REG_GPIO_INT_LVL2 = 0x27,
REG_GPIO_INT_LVL3 = 0x28,
REG_DEBOUNCE_DIS1 = 0x29,
REG_DEBOUNCE_DIS2 = 0x2A,
REG_DEBOUNCE_DIS3 = 0x2B,
REG_GPIO_PULL1 = 0x2C,
REG_GPIO_PULL2 = 0x2D,
REG_GPIO_PULL3 = 0x2E,
REG_LAST_RESERVED = 0x2F,
};
};
#endif

77
Release_Notes/NeoPixel.md Normal file
View File

@ -0,0 +1,77 @@
NeoPixel support
The IO_NeoPixel.h driver supports the adafruit neopixel seesaw board. It turns each pixel into an individual VPIN which can be given a colour and turned on or off using the new <o> command or the NEOPIXEL Exrail macro. Exrail SIGNALS can also drive a single pixel signal or multiple separate pixels.
1. Defining the hardware driver:
Add a driver definition in myAutomation.h for each adafruit I2C driver.
HAL(neoPixel, firstVpin, numberOfPixels [, mode [, i2caddress])
Where mode is selected from the various pixel string types which have varying
colour order or refresh frequency. For MOST strings this mode will be NEO_GRB but for others refer to the comments in IO_NeoPixel.h
If omitted the node and i2caddress default to NEO_GRB, 0x60.
HAL(NeoPixel,1000,20)
This is a NeoPixel driver defaulting to I2C aqddress 0x60 for a GRB pixel string. Pixels are given vpin numbers from 1000 to 1019.
HAL(NeoPixel,1020,20,NEO_GRB,0x61)
This is a NeoPixel driver on i2c address 0x61
2. Setting pixels from the < > commands.
By default, each pixel in the string is created as white but switched off.
Each pixel has a vpin starting from the first vpin in the HAL definitions.
<o vpin> switches pixel on (same as <z vpin>) e.g. <o 1005>
<o -vpin> switches pixel off (same as <z -vpin>) e.g. <o -1003>
(the z commands work on pixels the same as other gpio pins.)
<o [-]vpin count> switches on/off count pixels starting at vpin. e.g <o 1000 5>
Note: it IS acceptable to switch across 2 strings of pixels if they are contiguous vpin ranges. It is also interesting that this command doesnt care if the vpins are NeoPixel or any other type, so it can be used to switch a range of other pin types.
<o [-]vpin red green blue [count]> sets the colour and on/off status of a pin or pins. Each colour is 0..255 e.g. <o 1005 255 255 0> sets pin 1005 to bright yellow and ON, <0 -1006 0 0 255 10> sets pins 1006 to 1015 (10 pins) to bright blue but OFF.
Note: If you set a pin to a colour, you can turn it on and off without having to reset the colour every time. This is something the adafruit seesaw library can't do and is just one of several reasons why we dont use it.
3. Setting pixels from EXRAIL
The new NEOPIXEL macro provides the same functionality as the <o [-]vpin red green blue [count]> command above.
NEOPIXEL([-]vpin, red, green, blue [,count])
Setting pixels on or off (without colour change) can be done with SET/RESET [currently there is no set range facility but that may be added as a general exrail thing... watch this space]
Because the pixels obey set/reset, the BLINK command can also be used to control blinking a pixel.
4. EXRAIL pixel signals.
There are two types possible, a mast with separate fixed colour pixels for each aspect, or a mast with one multiple colour pixel for all aspects.
For separate pixels, the colours should be established at startup and a normal SIGNALH macro used.
AUTOSTART
SIGNALH(1010,1011,1012)
NEOPIXEL(1010,255,0,0)
NEOPIXEL(1011,128,128,0)
NEOPIXEL(1012,0,255,0)
RED(1010) // force signal state otherwise all 3 lights will be on
DONE
For signals with 1 pixel, the NEOPIXEL_SIGNAL macro will create a signal
NEOPIXEL_SIGNAL(vpin,redfx,amberfx,greenfx)
** Changed... ****
The fx values above can be created by the NeoRGB macro so a bright red would be NeoRGB(255,0,0) bright green NeoRGB(0,255,0) and amber something like NeoRGB(255,100,0)
NeoRGB creates a single int32_t value so it can be used in several ways as convenient.
// create 1-lamp signal with NeoRGB colours
NEOPIXEL_SIGNAL(1000,NeoRGB(255,0,0),NeoRGB(255,100,0),NeoRGB(0,255,0))
// Create 1-lamp signal with named colours.
// This is better if you have multiple signals.
// (Note: ALIAS is not suitable due to word length defaults)
#define REDLAMP NeoRGB(255,0,0)
#define AMBERLAMP NeoRGB(255,100,0)
#define GREENLAMP NeoRGB(0,255,0)
NEOPIXEL_SIGNAL(1001,REDLAMP,AMBERLAMP,GREENLAMP)
// Create 1-lamp signal with web type RGB colours
// (Using blue for the amber signal , just testing)
NEOPIXEL_SIGNAL(1002,0xFF0000,0x0000FF,0x00FF00)

View File

@ -1,7 +1,7 @@
/*
* © 2022 Paul M. Antoine
* © 2021 Chris Harlow
* © 2022 Harald Barth
* © 2022 2024 Harald Barth
* All rights reserved.
*
* This file is part of DCC++EX
@ -23,6 +23,7 @@
#include "SerialManager.h"
#include "DCCEXParser.h"
#include "StringFormatter.h"
#include "DIAG.h"
#ifdef ARDUINO_ARCH_ESP32
#ifdef SERIAL_BT_COMMANDS
@ -36,6 +37,10 @@ BluetoothSerial SerialBT;
#endif //COMMANDS
#endif //ESP32
static const byte PAYLOAD_FALSE = 0;
static const byte PAYLOAD_NORMAL = 1;
static const byte PAYLOAD_STRING = 2;
SerialManager * SerialManager::first=NULL;
SerialManager::SerialManager(Stream * myserial) {
@ -43,7 +48,7 @@ SerialManager::SerialManager(Stream * myserial) {
next=first;
first=this;
bufferLength=0;
inCommandPayload=false;
inCommandPayload=PAYLOAD_FALSE;
}
void SerialManager::init() {
@ -68,7 +73,11 @@ void SerialManager::init() {
new SerialManager(&Serial3);
#endif
#ifdef SERIAL2_COMMANDS
#ifdef ARDUINO_ARCH_ESP32
Serial2.begin(115200, SERIAL_8N1, 16, 17); // GPIO 16 RXD2; GPIO 17 TXD2 on ESP32
#else // not ESP32
Serial2.begin(115200);
#endif // ESP32
new SerialManager(&Serial2);
#endif
#ifdef SERIAL1_COMMANDS
@ -88,7 +97,11 @@ void SerialManager::init() {
}
#endif
#ifdef SABERTOOTH
#ifdef ARDUINO_ARCH_ESP32
Serial2.begin(9600, SERIAL_8N1, 16, 17); // GPIO 16 RXD2; GPIO 17 TXD2 on ESP32
#else
Serial2.begin(9600);
#endif
#endif
}
@ -104,23 +117,39 @@ void SerialManager::loop() {
}
void SerialManager::loop2() {
while (serial->available()) {
char ch = serial->read();
if (ch == '<') {
inCommandPayload = true;
bufferLength = 0;
buffer[0] = '\0';
}
else if (inCommandPayload) {
if (bufferLength < (COMMAND_BUFFER_SIZE-1))
buffer[bufferLength++] = ch;
if (ch == '>') {
buffer[bufferLength] = '\0';
DCCEXParser::parse(serial, buffer, NULL);
inCommandPayload = false;
break;
}
while (serial->available()) {
char ch = serial->read();
if (!inCommandPayload) {
if (ch == '<') {
inCommandPayload = PAYLOAD_NORMAL;
bufferLength = 0;
buffer[0] = '\0';
}
} else { // if (inCommandPayload)
if (bufferLength < (COMMAND_BUFFER_SIZE-1))
buffer[bufferLength++] = ch;
if (inCommandPayload > PAYLOAD_NORMAL) {
if (inCommandPayload > 32 + 2) { // String way too long
ch = '>'; // we end this nonsense
inCommandPayload = PAYLOAD_NORMAL;
DIAG(F("Parse error: Unbalanced string"));
// fall through to ending parsing below
} else if (ch == '"') { // String end
inCommandPayload = PAYLOAD_NORMAL;
continue; // do not fall through
} else
inCommandPayload++;
}
if (inCommandPayload == PAYLOAD_NORMAL) {
if (ch == '>') {
buffer[bufferLength] = '\0';
DCCEXParser::parse(serial, buffer, NULL);
inCommandPayload = PAYLOAD_FALSE;
break;
} else if (ch == '"') {
inCommandPayload = PAYLOAD_STRING;
}
}
}
}
}

View File

@ -44,6 +44,6 @@ private:
SerialManager * next;
byte bufferLength;
byte buffer[COMMAND_BUFFER_SIZE];
bool inCommandPayload;
byte inCommandPayload;
};
#endif

View File

@ -322,6 +322,15 @@ void WiThrottle::locoAction(RingStream * stream, byte* aval, char throttleChar,
}
break;
}
case 'f': // Function key set, force function variant
{
bool pressed=aval[1]=='1';
int fKey = getInt(aval+2);
LOOPLOCOS(throttleChar, cab) {
DCC::setFn(myLocos[loco].cab,fKey, pressed);
}
break;
}
case 'q':
if (aval[1]=='V' || aval[1]=='R' ) { //qV or qR
// just flag the loco for broadcast and it will happen.

View File

@ -23,13 +23,13 @@
#include <vector>
#include "defines.h"
#include "ESPmDNS.h"
#include <WiFi.h>
#include "esp_wifi.h"
#include "WifiESP32.h"
#include "DIAG.h"
#include "RingStream.h"
#include "CommandDistributor.h"
#include "WiThrottle.h"
#include "DCC.h"
/*
#include "soc/rtc_wdt.h"
#include "esp_task_wdt.h"
@ -109,10 +109,13 @@ private:
bool inUse;
};
// file scope variables
static std::vector<NetworkClient> clients; // a list to hold all clients
static WiFiServer *server = NULL;
static RingStream *outboundRing = new RingStream(10240);
static bool APmode = false;
// init of static class scope variables
bool WifiESP::wifiUp = false;
WiFiServer *WifiESP::server = NULL;
#ifdef WIFI_TASK_ON_CORE0
void wifiLoop(void *){
@ -128,6 +131,30 @@ char asciitolower(char in) {
return in;
}
void WifiESP::teardown() {
// stop all locos
DCC::setThrottle(0,1,1); // this broadcasts speed 1(estop) and sets all reminders to speed 1.
// terminate all clients connections
while (!clients.empty()) {
// pop_back() should invoke destructor which does stop()
// on the underlying TCP connction
clients.pop_back();
}
// stop server
if (server != NULL) {
server->stop();
server->close();
server->end();
DIAG(F("server stop, close, end"));
}
// terminate MDNS anouncement
mdns_service_remove_all();
mdns_free();
// stop WiFi
WiFi.disconnect(true);
wifiUp = false;
}
bool WifiESP::setup(const char *SSid,
const char *password,
const char *hostname,
@ -136,8 +163,10 @@ bool WifiESP::setup(const char *SSid,
const bool forceAP) {
bool havePassword = true;
bool haveSSID = true;
bool wifiUp = false;
// bool wifiUp = false;
uint8_t tries = 40;
if (wifiUp)
teardown();
//#ifdef SERIAL_BT_COMMANDS
//return false;
@ -265,7 +294,7 @@ bool WifiESP::setup(const char *SSid,
if(!MDNS.begin(hostname)) {
DIAG(F("Wifi setup failed to start mDNS"));
}
if(!MDNS.addService("withrottle", "tcp", 2560)) {
if(!MDNS.addService("withrottle", "tcp", port)) {
DIAG(F("Wifi setup failed to add withrottle service to mDNS"));
}

View File

@ -22,6 +22,7 @@
#ifndef WifiESP32_h
#define WifiESP32_h
#include <WiFi.h>
#include "FSH.h"
class WifiESP
@ -36,6 +37,9 @@ public:
const bool forceAP);
static void loop();
private:
static void teardown();
static bool wifiUp;
static WiFiServer *server;
};
#endif //WifiESP8266_h
#endif //ESP8266

View File

@ -104,10 +104,35 @@ lib_deps =
${env.lib_deps}
arduino-libraries/Ethernet
SPI
MDNS_Generic
lib_ignore = WiFi101
WiFi101_Generic
WiFiEspAT
WiFiMulti_Generic
WiFiNINA_Generic
monitor_speed = 115200
monitor_echo = yes
build_flags =
[env:mega2560-eth]
platform = atmelavr
board = megaatmega2560
framework = arduino
lib_deps =
${env.lib_deps}
arduino-libraries/Ethernet
MDNS_Generic
SPI
lib_ignore = WiFi101
WiFi101_Generic
WiFiEspAT
WiFiMulti_Generic
WiFiNINA_Generic
monitor_speed = 115200
monitor_echo = yes
[env:mega328]
platform = atmelavr
board = uno
@ -222,14 +247,14 @@ monitor_echo = yes
; Commented out by default as the F446ZE needs variant files
; installed before you can let PlatformIO see this
;
; [env:Nucleo-F446ZE]
; platform = ststm32
; board = nucleo_f446ze
; framework = arduino
; lib_deps = ${env.lib_deps}
; build_flags = -std=c++17 -Os -g2 -Wunused-variable
; monitor_speed = 115200
; monitor_echo = yes
[env:Nucleo-F446ZE]
platform = ststm32
board = nucleo_f446ze
framework = arduino
lib_deps = ${env.lib_deps}
build_flags = -std=c++17 -Os -g2 -Wunused-variable
monitor_speed = 115200
monitor_echo = yes
; Commented out by default as the F412ZG needs variant files
; installed before you can let PlatformIO see this
@ -246,6 +271,24 @@ monitor_echo = yes
; Experimental - Ethernet work still in progress
;
[env:Nucleo-F429ZI]
platform = ststm32
board = nucleo_f429zi
framework = arduino
lib_deps = ${env.lib_deps}
stm32duino/STM32Ethernet @ ^1.3.0
stm32duino/STM32duino LwIP @ ^2.1.2
MDNS_Generic
lib_ignore = WiFi101
WiFi101_Generic
WiFiEspAT
WiFiMulti_Generic
WiFiNINA_Generic
build_flags = -std=c++17 -Os -g2 -Wunused-variable
monitor_speed = 115200
monitor_echo = yes
upload_protocol = stlink
; [env:Nucleo-F429ZI]
; platform = ststm32
; board = nucleo_f429zi

View File

@ -3,7 +3,17 @@
#include "StringFormatter.h"
#define VERSION "5.2.74"
#define VERSION "5.2.80"
// 5.2.80 - EthernetInterface upgrade
// 5.2.79 - serial manager loop that handles quoted strings
// - WiFiESP32 reconfig
// 5.2.78 - NeoPixel support.
// - <o command
// - HAL driver
// - EXRAIL NEOPIXEL and NEOPIXEL_SIGNAL
// 5.2.77 - Withrottle: Implement "force function" subcommand "f"
// 5.2.76 - Bugfix: EXRAIL: Catch CV read errors in the callback
// 5.2.75 - Bugfix: Serial lines 4 to 6 OK
// 5.2.74 - Bugfix: ESP32 turn on the joined prog (as main) again after a prog operation
// 5.2.73 - Bugfix: STM32 further fixes to shadowPORT entries in TrackManager.cpp for PORTG and PORTH
// 5.2.72 - Bugfix: added shadowPORT entries in TrackManager.cpp for PORTG and PORTH on STM32, fixed typo in MotorDriver.cpp