mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-11-23 08:06:13 +01:00
Compare commits
25 Commits
5f53d2415b
...
d33fd5a7bb
Author | SHA1 | Date | |
---|---|---|---|
|
d33fd5a7bb | ||
|
fe2f705fa9 | ||
|
2606d73d93 | ||
|
4ab77c21ed | ||
|
b53384ab51 | ||
|
b026417efb | ||
|
7ffbd9d0e8 | ||
|
6fa5511670 | ||
|
c07ac38ab1 | ||
|
7395aa4af8 | ||
|
2397b773d7 | ||
|
9a08f2df63 | ||
|
ed853eef1d | ||
|
05e77c924e | ||
|
c5c5609fc6 | ||
|
9c263062e4 | ||
|
f39fd89fbd | ||
|
4e57a80265 | ||
|
27dc8059d7 | ||
|
dc2eae499f | ||
|
c518dcdc0b | ||
|
e6047f6693 | ||
|
96c4757cc6 | ||
|
60e564df51 | ||
|
a8b4e39733 |
|
@ -37,7 +37,7 @@ int16_t lastclocktime;
|
||||||
int8_t lastclockrate;
|
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
|
// use a buffer to allow broadcast
|
||||||
StringBuffer * CommandDistributor::broadcastBufferWriter=new StringBuffer();
|
StringBuffer * CommandDistributor::broadcastBufferWriter=new StringBuffer();
|
||||||
template<typename... Targs> void CommandDistributor::broadcastReply(clientType type, Targs... msg){
|
template<typename... Targs> void CommandDistributor::broadcastReply(clientType type, Targs... msg){
|
||||||
|
@ -248,6 +248,10 @@ void CommandDistributor::broadcastLoco(byte slot) {
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void CommandDistributor::broadcastForgetLoco(int16_t loco) {
|
||||||
|
broadcastReply(COMMAND_TYPE, F("<l %d 0 1 0>\n<- %d>\n"), loco,loco);
|
||||||
|
}
|
||||||
|
|
||||||
void CommandDistributor::broadcastPower() {
|
void CommandDistributor::broadcastPower() {
|
||||||
char pstr[] = "? x";
|
char pstr[] = "? x";
|
||||||
for(byte t=0; t<TrackManager::MAX_TRACKS; t++)
|
for(byte t=0; t<TrackManager::MAX_TRACKS; t++)
|
||||||
|
|
|
@ -47,6 +47,7 @@ private:
|
||||||
public :
|
public :
|
||||||
static void parse(byte clientId,byte* buffer, RingStream * ring);
|
static void parse(byte clientId,byte* buffer, RingStream * ring);
|
||||||
static void broadcastLoco(byte slot);
|
static void broadcastLoco(byte slot);
|
||||||
|
static void broadcastForgetLoco(int16_t loco);
|
||||||
static void broadcastSensor(int16_t id, bool value);
|
static void broadcastSensor(int16_t id, bool value);
|
||||||
static void broadcastTurnout(int16_t id, bool isClosed);
|
static void broadcastTurnout(int16_t id, bool isClosed);
|
||||||
static void broadcastTurntable(int16_t id, uint8_t position, bool moving);
|
static void broadcastTurntable(int16_t id, uint8_t position, bool moving);
|
||||||
|
|
20
DCC.cpp
20
DCC.cpp
|
@ -271,6 +271,20 @@ uint32_t DCC::getFunctionMap(int cab) {
|
||||||
return (reg<0)?0:speedTable[reg].functions;
|
return (reg<0)?0:speedTable[reg].functions;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// saves DC frequency (0..3) in spare functions 29,30,31
|
||||||
|
void DCC::setDCFreq(int cab,byte freq) {
|
||||||
|
if (cab==0 || freq>3) return;
|
||||||
|
auto reg=lookupSpeedTable(cab,true);
|
||||||
|
// drop and replace F29,30,31 (top 3 bits)
|
||||||
|
auto newFunctions=speedTable[reg].functions & 0x1FFFFFFFUL;
|
||||||
|
if (freq==1) newFunctions |= (1UL<<29); // F29
|
||||||
|
else if (freq==2) newFunctions |= (1UL<<30); // F30
|
||||||
|
else if (freq==3) newFunctions |= (1UL<<31); // F31
|
||||||
|
if (newFunctions==speedTable[reg].functions) return; // no change
|
||||||
|
speedTable[reg].functions=newFunctions;
|
||||||
|
CommandDistributor::broadcastLoco(reg);
|
||||||
|
}
|
||||||
|
|
||||||
void DCC::setAccessory(int address, byte port, bool gate, byte onoff /*= 2*/) {
|
void DCC::setAccessory(int address, byte port, bool gate, byte onoff /*= 2*/) {
|
||||||
// onoff is tristate:
|
// onoff is tristate:
|
||||||
// 0 => send off packet
|
// 0 => send off packet
|
||||||
|
@ -728,11 +742,15 @@ void DCC::forgetLoco(int cab) { // removes any speed reminders for this loco
|
||||||
if (reg>=0) {
|
if (reg>=0) {
|
||||||
speedTable[reg].loco=0;
|
speedTable[reg].loco=0;
|
||||||
setThrottle2(cab,1); // ESTOP if this loco still on track
|
setThrottle2(cab,1); // ESTOP if this loco still on track
|
||||||
|
CommandDistributor::broadcastForgetLoco(cab);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
void DCC::forgetAllLocos() { // removes all speed reminders
|
void DCC::forgetAllLocos() { // removes all speed reminders
|
||||||
setThrottle2(0,1); // ESTOP all locos still on track
|
setThrottle2(0,1); // ESTOP all locos still on track
|
||||||
for (int i=0;i<MAX_LOCOS;i++) speedTable[i].loco=0;
|
for (int i=0;i<MAX_LOCOS;i++) {
|
||||||
|
if (speedTable[i].loco) CommandDistributor::broadcastForgetLoco(speedTable[i].loco);
|
||||||
|
speedTable[i].loco=0;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
byte DCC::loopStatus=0;
|
byte DCC::loopStatus=0;
|
||||||
|
|
1
DCC.h
1
DCC.h
|
@ -70,6 +70,7 @@ public:
|
||||||
static void changeFn(int cab, int16_t functionNumber);
|
static void changeFn(int cab, int16_t functionNumber);
|
||||||
static int8_t getFn(int cab, int16_t functionNumber);
|
static int8_t getFn(int cab, int16_t functionNumber);
|
||||||
static uint32_t getFunctionMap(int cab);
|
static uint32_t getFunctionMap(int cab);
|
||||||
|
static void setDCFreq(int cab,byte freq);
|
||||||
static void updateGroupflags(byte &flags, int16_t functionNumber);
|
static void updateGroupflags(byte &flags, int16_t functionNumber);
|
||||||
static void setAccessory(int address, byte port, bool gate, byte onoff = 2);
|
static void setAccessory(int address, byte port, bool gate, byte onoff = 2);
|
||||||
static bool setExtendedAccessory(int16_t address, int16_t value, byte repeats=3);
|
static bool setExtendedAccessory(int16_t address, int16_t value, byte repeats=3);
|
||||||
|
|
|
@ -642,6 +642,13 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
|
||||||
|
|
||||||
case 'F': // New command to call the new Loco Function API <F cab func 1|0>
|
case 'F': // New command to call the new Loco Function API <F cab func 1|0>
|
||||||
if(params!=3) break;
|
if(params!=3) break;
|
||||||
|
|
||||||
|
if (p[1]=="DCFREQ"_hk) { // <F cab DCFREQ 0..3>
|
||||||
|
if (p[2]<0 || p[2]>3) break;
|
||||||
|
DCC::setDCFreq(p[0],p[2]);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (Diag::CMD)
|
if (Diag::CMD)
|
||||||
DIAG(F("Setting loco %d F%d %S"), p[0], p[1], p[2] ? F("ON") : F("OFF"));
|
DIAG(F("Setting loco %d F%d %S"), p[0], p[1], p[2] ? F("ON") : F("OFF"));
|
||||||
if (DCC::setFn(p[0], p[1], p[2] == 1)) return;
|
if (DCC::setFn(p[0], p[1], p[2] == 1)) return;
|
||||||
|
|
58
EXRAIL2.cpp
58
EXRAIL2.cpp
|
@ -478,10 +478,15 @@ bool RMFT2::skipIfBlock() {
|
||||||
|
|
||||||
|
|
||||||
/* static */ void RMFT2::readLocoCallback(int16_t cv) {
|
/* 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
|
if (cv & LONG_ADDR_MARKER) { // maker bit indicates long addr
|
||||||
progtrackLocoId = cv ^ LONG_ADDR_MARKER; // remove marker bit to get real 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
|
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;
|
progtrackLocoId = -1;
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
|
@ -628,14 +633,16 @@ void RMFT2::loop2() {
|
||||||
skipIf=blinkState!=at_timeout;
|
skipIf=blinkState!=at_timeout;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OPCODE_AFTER: // waits for sensor to hit and then remain off for 0.5 seconds. (must come after an AT operation)
|
case OPCODE_AFTER: // waits for sensor to hit and then remain off for x mS.
|
||||||
|
// Note, this must come after an AT operation, which is
|
||||||
|
// automatically inserted by the AFTER macro.
|
||||||
if (readSensor(operand)) {
|
if (readSensor(operand)) {
|
||||||
// reset timer to half a second and keep waiting
|
// reset timer and keep waiting
|
||||||
waitAfter=millis();
|
waitAfter=millis();
|
||||||
delayMe(50);
|
delayMe(50);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (millis()-waitAfter < 500 ) return;
|
if (millis()-waitAfter < getOperand(1) ) return;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OPCODE_AFTEROVERLOAD: // waits for the power to be turned back on - either by power routine or button
|
case OPCODE_AFTEROVERLOAD: // waits for the power to be turned back on - either by power routine or button
|
||||||
|
@ -716,41 +723,7 @@ void RMFT2::loop2() {
|
||||||
|
|
||||||
case OPCODE_SETFREQ:
|
case OPCODE_SETFREQ:
|
||||||
// Frequency is default 0, or 1, 2,3
|
// Frequency is default 0, or 1, 2,3
|
||||||
//if (loco) DCC::setFn(loco,operand,true);
|
DCC::setDCFreq(loco,operand);
|
||||||
switch (operand) {
|
|
||||||
case 0: // default - all F-s off
|
|
||||||
if (loco) {
|
|
||||||
DCC::setFn(loco,29,false);
|
|
||||||
DCC::setFn(loco,30,false);
|
|
||||||
DCC::setFn(loco,31,false);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case 1:
|
|
||||||
if (loco) {
|
|
||||||
DCC::setFn(loco,29,true);
|
|
||||||
DCC::setFn(loco,30,false);
|
|
||||||
DCC::setFn(loco,31,false);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case 2:
|
|
||||||
if (loco) {
|
|
||||||
DCC::setFn(loco,29,false);
|
|
||||||
DCC::setFn(loco,30,true);
|
|
||||||
DCC::setFn(loco,31,false);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case 3:
|
|
||||||
if (loco) {
|
|
||||||
DCC::setFn(loco,29,false);
|
|
||||||
DCC::setFn(loco,30,false);
|
|
||||||
DCC::setFn(loco,31,true);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
; // do nothing
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OPCODE_RESUME:
|
case OPCODE_RESUME:
|
||||||
|
@ -953,11 +926,10 @@ void RMFT2::loop2() {
|
||||||
delayMe(100);
|
delayMe(100);
|
||||||
return; // still waiting for callback
|
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;
|
loco=progtrackLocoId;
|
||||||
speedo=0;
|
speedo=0;
|
||||||
forward=true;
|
forward=true;
|
||||||
|
|
|
@ -195,7 +195,7 @@
|
||||||
#ifndef RMFT2_UNDEF_ONLY
|
#ifndef RMFT2_UNDEF_ONLY
|
||||||
#define ACTIVATE(addr,subaddr)
|
#define ACTIVATE(addr,subaddr)
|
||||||
#define ACTIVATEL(addr)
|
#define ACTIVATEL(addr)
|
||||||
#define AFTER(sensor_id)
|
#define AFTER(sensor_id,timer...)
|
||||||
#define AFTEROVERLOAD(track_id)
|
#define AFTEROVERLOAD(track_id)
|
||||||
#define ALIAS(name,value...)
|
#define ALIAS(name,value...)
|
||||||
#define AMBER(signal_id)
|
#define AMBER(signal_id)
|
||||||
|
@ -334,7 +334,7 @@
|
||||||
#define SET_TRACK(track,mode)
|
#define SET_TRACK(track,mode)
|
||||||
#define SET_POWER(track,onoff)
|
#define SET_POWER(track,onoff)
|
||||||
#define SETLOCO(loco)
|
#define SETLOCO(loco)
|
||||||
#define SETFREQ(loco,freq)
|
#define SETFREQ(freq)
|
||||||
#define SIGNAL(redpin,amberpin,greenpin)
|
#define SIGNAL(redpin,amberpin,greenpin)
|
||||||
#define SIGNALH(redpin,amberpin,greenpin)
|
#define SIGNALH(redpin,amberpin,greenpin)
|
||||||
#define SPEED(speed)
|
#define SPEED(speed)
|
||||||
|
|
|
@ -463,7 +463,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
|
||||||
|
|
||||||
#define ACTIVATE(addr,subaddr) OPCODE_DCCACTIVATE,V(addr<<3 | subaddr<<1 | 1),
|
#define ACTIVATE(addr,subaddr) OPCODE_DCCACTIVATE,V(addr<<3 | subaddr<<1 | 1),
|
||||||
#define ACTIVATEL(addr) OPCODE_DCCACTIVATE,V((addr+3)<<1 | 1),
|
#define ACTIVATEL(addr) OPCODE_DCCACTIVATE,V((addr+3)<<1 | 1),
|
||||||
#define AFTER(sensor_id) OPCODE_AT,V(sensor_id),OPCODE_AFTER,V(sensor_id),
|
#define AFTER(sensor_id,timer...) OPCODE_AT,V(sensor_id),OPCODE_AFTER,V(sensor_id),OPCODE_PAD,V(#timer[0]?timer+0:500),
|
||||||
#define AFTEROVERLOAD(track_id) OPCODE_AFTEROVERLOAD,V(TRACK_NUMBER_##track_id),
|
#define AFTEROVERLOAD(track_id) OPCODE_AFTEROVERLOAD,V(TRACK_NUMBER_##track_id),
|
||||||
#define ALIAS(name,value...)
|
#define ALIAS(name,value...)
|
||||||
#define AMBER(signal_id) OPCODE_AMBER,V(signal_id),
|
#define AMBER(signal_id) OPCODE_AMBER,V(signal_id),
|
||||||
|
@ -620,7 +620,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
|
||||||
#define SET_TRACK(track,mode) OPCODE_SET_TRACK,V(TRACK_MODE_##mode <<8 | TRACK_NUMBER_##track),
|
#define SET_TRACK(track,mode) OPCODE_SET_TRACK,V(TRACK_MODE_##mode <<8 | TRACK_NUMBER_##track),
|
||||||
#define SET_POWER(track,onoff) OPCODE_SET_POWER,V(TRACK_POWER_##onoff),OPCODE_PAD, V(TRACK_NUMBER_##track),
|
#define SET_POWER(track,onoff) OPCODE_SET_POWER,V(TRACK_POWER_##onoff),OPCODE_PAD, V(TRACK_NUMBER_##track),
|
||||||
#define SETLOCO(loco) OPCODE_SETLOCO,V(loco),
|
#define SETLOCO(loco) OPCODE_SETLOCO,V(loco),
|
||||||
#define SETFREQ(loco,freq) OPCODE_SETLOCO,V(loco), OPCODE_SETFREQ,V(freq),
|
#define SETFREQ(freq) OPCODE_SETFREQ,V(freq),
|
||||||
#define SIGNAL(redpin,amberpin,greenpin)
|
#define SIGNAL(redpin,amberpin,greenpin)
|
||||||
#define SIGNALH(redpin,amberpin,greenpin)
|
#define SIGNALH(redpin,amberpin,greenpin)
|
||||||
#define SPEED(speed) OPCODE_SPEED,V(speed),
|
#define SPEED(speed) OPCODE_SPEED,V(speed),
|
||||||
|
|
|
@ -1 +1 @@
|
||||||
#define GITHUB_SHA "devel-202406182019Z"
|
#define GITHUB_SHA "devel-202409121220Z"
|
||||||
|
|
|
@ -547,6 +547,6 @@ protected:
|
||||||
#include "IO_duinoNodes.h"
|
#include "IO_duinoNodes.h"
|
||||||
#include "IO_EXIOExpander.h"
|
#include "IO_EXIOExpander.h"
|
||||||
#include "IO_trainbrains.h"
|
#include "IO_trainbrains.h"
|
||||||
|
#include "IO_EncoderThrottle.h"
|
||||||
|
|
||||||
#endif // iodevice_h
|
#endif // iodevice_h
|
||||||
|
|
144
IO_EncoderThrottle.cpp
Normal file
144
IO_EncoderThrottle.cpp
Normal file
|
@ -0,0 +1,144 @@
|
||||||
|
/*
|
||||||
|
* © 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_EncoderThrottle device driver uses a rotary encoder connected to vpins
|
||||||
|
* to drive a loco.
|
||||||
|
* Loco id is selected by writeAnalog.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "IODevice.h"
|
||||||
|
#include "DIAG.h"
|
||||||
|
#include "DCC.h"
|
||||||
|
|
||||||
|
const byte _DIR_CW = 0x10; // Clockwise step
|
||||||
|
const byte _DIR_CCW = 0x20; // Counter-clockwise step
|
||||||
|
|
||||||
|
const byte transition_table[5][4]= {
|
||||||
|
{0,1,3,0}, // 0: 00
|
||||||
|
{1,1,1,2 | _DIR_CW}, // 1: 00->01
|
||||||
|
{2,2,0,2}, // 2: 00->01->11
|
||||||
|
{3,3,3,4 | _DIR_CCW}, // 3: 00->10
|
||||||
|
{4,0,4,4} // 4: 00->10->11
|
||||||
|
};
|
||||||
|
|
||||||
|
const byte _STATE_MASK = 0x07;
|
||||||
|
const byte _DIR_MASK = 0x30;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void EncoderThrottle::create(VPIN firstVpin, int dtPin, int clkPin, int clickPin, byte notch) {
|
||||||
|
if (checkNoOverlap(firstVpin)) new EncoderThrottle(firstVpin, dtPin,clkPin,clickPin,notch);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Constructor
|
||||||
|
EncoderThrottle::EncoderThrottle(VPIN firstVpin, int dtPin, int clkPin, int clickPin, byte notch){
|
||||||
|
_firstVpin = firstVpin;
|
||||||
|
_nPins = 1;
|
||||||
|
_I2CAddress = 0;
|
||||||
|
_dtPin=dtPin;
|
||||||
|
_clkPin=clkPin;
|
||||||
|
_clickPin=clickPin;
|
||||||
|
_notch=notch;
|
||||||
|
_locoid=0;
|
||||||
|
_stopState=xrSTOP;
|
||||||
|
_rocoState=0;
|
||||||
|
_prevpinstate=4; // not 01..11
|
||||||
|
IODevice::configureInput(dtPin,true);
|
||||||
|
IODevice::configureInput(clkPin,true);
|
||||||
|
IODevice::configureInput(clickPin,true);
|
||||||
|
addDevice(this);
|
||||||
|
_display();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void EncoderThrottle::_loop(unsigned long currentMicros) {
|
||||||
|
if (_locoid==0) return; // not in use
|
||||||
|
|
||||||
|
// Clicking down on the roco, stops the loco and sets the direction as unknown.
|
||||||
|
if (IODevice::read(_clickPin)) {
|
||||||
|
if (_stopState==xrSTOP) return; // debounced multiple stops
|
||||||
|
DCC::setThrottle(_locoid,1,DCC::getThrottleDirection(_locoid));
|
||||||
|
_stopState=xrSTOP;
|
||||||
|
DIAG(F("DRIVE %d STOP"),_locoid);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// read roco pins and detect state change
|
||||||
|
byte pinstate = (IODevice::read(_dtPin) << 1) | IODevice::read(_clkPin);
|
||||||
|
if (pinstate==_prevpinstate) return;
|
||||||
|
_prevpinstate=pinstate;
|
||||||
|
|
||||||
|
_rocoState = transition_table[_rocoState & _STATE_MASK][pinstate];
|
||||||
|
if ((_rocoState & _DIR_MASK) == 0) return; // no value change
|
||||||
|
|
||||||
|
int change=(_rocoState & _DIR_CW)?+1:-1;
|
||||||
|
// handle roco change -1 or +1 (clockwise)
|
||||||
|
|
||||||
|
if (_stopState==xrSTOP) {
|
||||||
|
// first move after button press sets the direction. (clockwise=fwd)
|
||||||
|
_stopState=change>0?xrFWD:xrREV;
|
||||||
|
}
|
||||||
|
|
||||||
|
// when going fwd, clockwise increases speed.
|
||||||
|
// but when reversing, anticlockwise increases speed.
|
||||||
|
// This is similar to a center-zero pot control but with
|
||||||
|
// the added safety that you cant panic-spin into the other
|
||||||
|
// direction.
|
||||||
|
if (_stopState==xrREV) change=-change;
|
||||||
|
// manage limits
|
||||||
|
int oldspeed=DCC::getThrottleSpeed(_locoid);
|
||||||
|
if (oldspeed==1)oldspeed=0; // break out of estop
|
||||||
|
int newspeed=change>0 ? (min((oldspeed+_notch),126)) : (max(0,(oldspeed-_notch)));
|
||||||
|
if (newspeed==1) newspeed=0; // normal decelereated stop.
|
||||||
|
if (oldspeed!=newspeed) {
|
||||||
|
DIAG(F("DRIVE %d notch %S %d %S"),_locoid,
|
||||||
|
change>0?F("UP"):F("DOWN"),_notch,
|
||||||
|
_stopState==xrFWD?F("FWD"):F("REV"));
|
||||||
|
DCC::setThrottle(_locoid,newspeed,_stopState==xrFWD);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Selocoid as analog value to start drive
|
||||||
|
// use <z vpin locoid [notch]>
|
||||||
|
void EncoderThrottle::_writeAnalogue(VPIN vpin, int value, uint8_t param1, uint16_t param2) {
|
||||||
|
(void) param2;
|
||||||
|
_locoid=value;
|
||||||
|
if (param1>0) _notch=param1;
|
||||||
|
_rocoState=0;
|
||||||
|
|
||||||
|
// If loco is moving, we inherit direction from it.
|
||||||
|
_stopState=xrSTOP;
|
||||||
|
if (_locoid>0) {
|
||||||
|
auto speedbyte=DCC::getThrottleSpeedByte(_locoid);
|
||||||
|
if ((speedbyte & 0x7f) >1) {
|
||||||
|
// loco is moving
|
||||||
|
_stopState= (speedbyte & 0x80)?xrFWD:xrREV;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
_display();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void EncoderThrottle::_display() {
|
||||||
|
DIAG(F("DRIVE vpin %d loco %d notch %d"),_firstVpin,_locoid,_notch);
|
||||||
|
}
|
||||||
|
|
53
IO_EncoderThrottle.h
Normal file
53
IO_EncoderThrottle.h
Normal file
|
@ -0,0 +1,53 @@
|
||||||
|
/*
|
||||||
|
* © 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_EncoderThrottle device driver uses a rotary encoder connected to vpins
|
||||||
|
* to drive a loco.
|
||||||
|
* Loco id is selected by writeAnalog.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef IO_EncoderThrottle_H
|
||||||
|
#define IO_EncoderThrottle_H
|
||||||
|
#include "IODevice.h"
|
||||||
|
|
||||||
|
class EncoderThrottle : public IODevice {
|
||||||
|
public:
|
||||||
|
|
||||||
|
static void create(VPIN firstVpin, int dtPin, int clkPin, int clickPin, byte notch=10);
|
||||||
|
|
||||||
|
private:
|
||||||
|
int _dtPin,_clkPin,_clickPin, _locoid, _notch,_prevpinstate;
|
||||||
|
enum {xrSTOP,xrFWD,xrREV} _stopState;
|
||||||
|
byte _rocoState;
|
||||||
|
|
||||||
|
// Constructor
|
||||||
|
EncoderThrottle(VPIN firstVpin, int dtPin, int clkPin, int clickPin, byte notch);
|
||||||
|
|
||||||
|
void _loop(unsigned long currentMicros) override ;
|
||||||
|
|
||||||
|
// Selocoid as analog value to start drive
|
||||||
|
// use <z vpin locoid [notch]>
|
||||||
|
void _writeAnalogue(VPIN vpin, int value, uint8_t param1, uint16_t param2) override;
|
||||||
|
|
||||||
|
void _display() override ;
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif
|
|
@ -1,5 +1,6 @@
|
||||||
/*
|
/*
|
||||||
* © 2022-2024 Paul M Antoine
|
* © 2022-2024 Paul M Antoine
|
||||||
|
* © 2024 Herb Morton
|
||||||
* © 2021 Mike S
|
* © 2021 Mike S
|
||||||
* © 2021 Fred Decker
|
* © 2021 Fred Decker
|
||||||
* © 2020-2023 Harald Barth
|
* © 2020-2023 Harald Barth
|
||||||
|
@ -98,7 +99,7 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
|
||||||
if (HAVE_PORTH(fastSignalPin.inout == &PORTH)) {
|
if (HAVE_PORTH(fastSignalPin.inout == &PORTH)) {
|
||||||
DIAG(F("Found PORTH pin %d"),signalPin);
|
DIAG(F("Found PORTH pin %d"),signalPin);
|
||||||
fastSignalPin.shadowinout = fastSignalPin.inout;
|
fastSignalPin.shadowinout = fastSignalPin.inout;
|
||||||
fastSignalPin.inout = &shadowPORTF;
|
fastSignalPin.inout = &shadowPORTH;
|
||||||
}
|
}
|
||||||
|
|
||||||
signalPin2=signal_pin2;
|
signalPin2=signal_pin2;
|
||||||
|
|
|
@ -68,7 +68,11 @@ void SerialManager::init() {
|
||||||
new SerialManager(&Serial3);
|
new SerialManager(&Serial3);
|
||||||
#endif
|
#endif
|
||||||
#ifdef SERIAL2_COMMANDS
|
#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);
|
Serial2.begin(115200);
|
||||||
|
#endif // ESP32
|
||||||
new SerialManager(&Serial2);
|
new SerialManager(&Serial2);
|
||||||
#endif
|
#endif
|
||||||
#ifdef SERIAL1_COMMANDS
|
#ifdef SERIAL1_COMMANDS
|
||||||
|
@ -88,7 +92,11 @@ void SerialManager::init() {
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#ifdef SABERTOOTH
|
#ifdef SABERTOOTH
|
||||||
|
#ifdef ARDUINO_ARCH_ESP32
|
||||||
Serial2.begin(9600, SERIAL_8N1, 16, 17); // GPIO 16 RXD2; GPIO 17 TXD2 on ESP32
|
Serial2.begin(9600, SERIAL_8N1, 16, 17); // GPIO 16 RXD2; GPIO 17 TXD2 on ESP32
|
||||||
|
#else
|
||||||
|
Serial2.begin(9600);
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -139,6 +139,7 @@ void StringFormatter::send2(Print * stream,const FSH* format, va_list args) {
|
||||||
case 'd': printPadded(stream,va_arg(args, int), formatWidth, formatLeft); break;
|
case 'd': printPadded(stream,va_arg(args, int), formatWidth, formatLeft); break;
|
||||||
case 'u': printPadded(stream,va_arg(args, unsigned int), formatWidth, formatLeft); break;
|
case 'u': printPadded(stream,va_arg(args, unsigned int), formatWidth, formatLeft); break;
|
||||||
case 'l': printPadded(stream,va_arg(args, long), formatWidth, formatLeft); break;
|
case 'l': printPadded(stream,va_arg(args, long), formatWidth, formatLeft); break;
|
||||||
|
case 'L': stream->print(va_arg(args, unsigned long), DEC); break;
|
||||||
case 'b': stream->print(va_arg(args, int), BIN); break;
|
case 'b': stream->print(va_arg(args, int), BIN); break;
|
||||||
case 'o': stream->print(va_arg(args, int), OCT); break;
|
case 'o': stream->print(va_arg(args, int), OCT); break;
|
||||||
case 'x': stream->print((unsigned int)va_arg(args, unsigned int), HEX); break;
|
case 'x': stream->print((unsigned int)va_arg(args, unsigned int), HEX); break;
|
||||||
|
|
|
@ -1,6 +1,8 @@
|
||||||
/*
|
/*
|
||||||
* © 2022 Chris Harlow
|
* © 2022 Chris Harlow
|
||||||
* © 2022-2024 Harald Barth
|
* © 2022-2024 Harald Barth
|
||||||
|
* © 2023-2024 Paul M. Antoine
|
||||||
|
* © 2024 Herb Morton
|
||||||
* © 2023 Colin Murdoch
|
* © 2023 Colin Murdoch
|
||||||
* All rights reserved.
|
* All rights reserved.
|
||||||
*
|
*
|
||||||
|
@ -149,6 +151,8 @@ void TrackManager::setDCCSignal( bool on) {
|
||||||
HAVE_PORTD(shadowPORTD=PORTD);
|
HAVE_PORTD(shadowPORTD=PORTD);
|
||||||
HAVE_PORTE(shadowPORTE=PORTE);
|
HAVE_PORTE(shadowPORTE=PORTE);
|
||||||
HAVE_PORTF(shadowPORTF=PORTF);
|
HAVE_PORTF(shadowPORTF=PORTF);
|
||||||
|
HAVE_PORTG(shadowPORTF=PORTG);
|
||||||
|
HAVE_PORTH(shadowPORTF=PORTH);
|
||||||
APPLY_BY_MODE(TRACK_MODE_MAIN,setSignal(on));
|
APPLY_BY_MODE(TRACK_MODE_MAIN,setSignal(on));
|
||||||
HAVE_PORTA(PORTA=shadowPORTA);
|
HAVE_PORTA(PORTA=shadowPORTA);
|
||||||
HAVE_PORTB(PORTB=shadowPORTB);
|
HAVE_PORTB(PORTB=shadowPORTB);
|
||||||
|
@ -156,6 +160,8 @@ void TrackManager::setDCCSignal( bool on) {
|
||||||
HAVE_PORTD(PORTD=shadowPORTD);
|
HAVE_PORTD(PORTD=shadowPORTD);
|
||||||
HAVE_PORTE(PORTE=shadowPORTE);
|
HAVE_PORTE(PORTE=shadowPORTE);
|
||||||
HAVE_PORTF(PORTF=shadowPORTF);
|
HAVE_PORTF(PORTF=shadowPORTF);
|
||||||
|
HAVE_PORTG(shadowPORTF=PORTG);
|
||||||
|
HAVE_PORTH(shadowPORTF=PORTH);
|
||||||
}
|
}
|
||||||
|
|
||||||
// setPROGSignal(), called from interrupt context
|
// setPROGSignal(), called from interrupt context
|
||||||
|
@ -167,6 +173,8 @@ void TrackManager::setPROGSignal( bool on) {
|
||||||
HAVE_PORTD(shadowPORTD=PORTD);
|
HAVE_PORTD(shadowPORTD=PORTD);
|
||||||
HAVE_PORTE(shadowPORTE=PORTE);
|
HAVE_PORTE(shadowPORTE=PORTE);
|
||||||
HAVE_PORTF(shadowPORTF=PORTF);
|
HAVE_PORTF(shadowPORTF=PORTF);
|
||||||
|
HAVE_PORTG(shadowPORTF=PORTG);
|
||||||
|
HAVE_PORTH(shadowPORTF=PORTH);
|
||||||
APPLY_BY_MODE(TRACK_MODE_PROG,setSignal(on));
|
APPLY_BY_MODE(TRACK_MODE_PROG,setSignal(on));
|
||||||
HAVE_PORTA(PORTA=shadowPORTA);
|
HAVE_PORTA(PORTA=shadowPORTA);
|
||||||
HAVE_PORTB(PORTB=shadowPORTB);
|
HAVE_PORTB(PORTB=shadowPORTB);
|
||||||
|
@ -174,6 +182,8 @@ void TrackManager::setPROGSignal( bool on) {
|
||||||
HAVE_PORTD(PORTD=shadowPORTD);
|
HAVE_PORTD(PORTD=shadowPORTD);
|
||||||
HAVE_PORTE(PORTE=shadowPORTE);
|
HAVE_PORTE(PORTE=shadowPORTE);
|
||||||
HAVE_PORTF(PORTF=shadowPORTF);
|
HAVE_PORTF(PORTF=shadowPORTF);
|
||||||
|
HAVE_PORTG(shadowPORTF=PORTG);
|
||||||
|
HAVE_PORTH(shadowPORTF=PORTH);
|
||||||
}
|
}
|
||||||
|
|
||||||
// setDCSignal(), called from normal context
|
// setDCSignal(), called from normal context
|
||||||
|
@ -631,23 +641,25 @@ void TrackManager::setJoinRelayPin(byte joinRelayPin) {
|
||||||
|
|
||||||
void TrackManager::setJoin(bool joined) {
|
void TrackManager::setJoin(bool joined) {
|
||||||
#ifdef ARDUINO_ARCH_ESP32
|
#ifdef ARDUINO_ARCH_ESP32
|
||||||
if (joined) {
|
if (joined) { // if we go into joined mode (PROG acts as MAIN)
|
||||||
FOR_EACH_TRACK(t) {
|
FOR_EACH_TRACK(t) {
|
||||||
if (track[t]->getMode() & TRACK_MODE_PROG) {
|
if (track[t]->getMode() & TRACK_MODE_PROG) { // find PROG track
|
||||||
tempProgTrack = t;
|
tempProgTrack = t; // remember PROG track
|
||||||
setTrackMode(t, TRACK_MODE_MAIN);
|
setTrackMode(t, TRACK_MODE_MAIN);
|
||||||
break;
|
track[t]->setPower(POWERMODE::ON); // if joined, always on
|
||||||
|
break; // there is only one prog track, done
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
if (tempProgTrack != MAX_TRACKS+1) {
|
if (tempProgTrack != MAX_TRACKS+1) {
|
||||||
// as setTrackMode with TRACK_MODE_PROG defaults to
|
// setTrackMode defaults to power off, so we
|
||||||
// power off, we will take the current power state
|
// need to preserve that state.
|
||||||
// of our track and then preserve that state.
|
POWERMODE tPTmode = track[tempProgTrack]->getPower(); // get current power status of this track
|
||||||
POWERMODE tPTmode = track[tempProgTrack]->getPower(); //get current power status of this track
|
setTrackMode(tempProgTrack, TRACK_MODE_PROG); // set track mode back to prog
|
||||||
setTrackMode(tempProgTrack, TRACK_MODE_PROG);
|
track[tempProgTrack]->setPower(tPTmode); // set power status as it was before
|
||||||
track[tempProgTrack]->setPower(tPTmode); //set track status as it was before
|
|
||||||
tempProgTrack = MAX_TRACKS+1;
|
tempProgTrack = MAX_TRACKS+1;
|
||||||
|
} else {
|
||||||
|
DIAG(F("Unjoin but no remembered prog track"));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -322,6 +322,15 @@ void WiThrottle::locoAction(RingStream * stream, byte* aval, char throttleChar,
|
||||||
}
|
}
|
||||||
break;
|
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':
|
case 'q':
|
||||||
if (aval[1]=='V' || aval[1]=='R' ) { //qV or qR
|
if (aval[1]=='V' || aval[1]=='R' ) { //qV or qR
|
||||||
// just flag the loco for broadcast and it will happen.
|
// just flag the loco for broadcast and it will happen.
|
||||||
|
|
|
@ -265,7 +265,7 @@ bool WifiESP::setup(const char *SSid,
|
||||||
if(!MDNS.begin(hostname)) {
|
if(!MDNS.begin(hostname)) {
|
||||||
DIAG(F("Wifi setup failed to start mDNS"));
|
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"));
|
DIAG(F("Wifi setup failed to add withrottle service to mDNS"));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
22
version.h
22
version.h
|
@ -3,7 +3,25 @@
|
||||||
|
|
||||||
#include "StringFormatter.h"
|
#include "StringFormatter.h"
|
||||||
|
|
||||||
#define VERSION "5.2.64"
|
#define VERSION "5.2.77"
|
||||||
|
// 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
|
||||||
|
// 5.2.71 - Broadcasts of loco forgets.
|
||||||
|
// 5.2.70 - IO_RocoDriver renamed to IO_EncoderThrottle.
|
||||||
|
// - and included in IODEvice.h (circular dependency removed)
|
||||||
|
// 5.2.69 - IO_RocoDriver. Direct drive train with rotary encoder hw.
|
||||||
|
// 5.2.68 - Revert function map to signed (from 5.2.66) to avoid
|
||||||
|
// incompatibilities with ED etc for F31 frequency flag.
|
||||||
|
// 5.2.67 - EXRAIL AFTER optional debounce time variable (default 500mS)
|
||||||
|
// - AFTER(42) == AFTER(42,500) sets time sensor must
|
||||||
|
// - be continuously off.
|
||||||
|
// 5.2.66 - <F cab DCFREQ 0..3>
|
||||||
|
// - EXRAIL SETFREQ drop loco param (breaking since 5.2.28)
|
||||||
|
// 5.2.65 - Speedup Exrail SETFREQ
|
||||||
// 5.2.64 - Bugfix: <0 PROG> updated to undo JOIN
|
// 5.2.64 - Bugfix: <0 PROG> updated to undo JOIN
|
||||||
// 5.2.63 - Implement WIFI_LED for ESP32, ESPduino32 and EX-CSB1, that is turned on when STA mode connects or AP mode is up
|
// 5.2.63 - Implement WIFI_LED for ESP32, ESPduino32 and EX-CSB1, that is turned on when STA mode connects or AP mode is up
|
||||||
// - Add BOOSTER_INPUT definitions for ESPduino32 and EX-CSB1 to config.example.h
|
// - Add BOOSTER_INPUT definitions for ESPduino32 and EX-CSB1 to config.example.h
|
||||||
|
@ -11,7 +29,7 @@
|
||||||
// 5.2.62 - Allow acks way longer than standard
|
// 5.2.62 - Allow acks way longer than standard
|
||||||
// 5.2.61 - Merg CBUS ACON/ACOF/ONACON/ONACOF Adapter interface.
|
// 5.2.61 - Merg CBUS ACON/ACOF/ONACON/ONACOF Adapter interface.
|
||||||
// - LCC Adapter interface throttled startup,
|
// - LCC Adapter interface throttled startup,
|
||||||
// (Breaking change woith Adapter base code)
|
// (Breaking change with Adapter base code)
|
||||||
// 5.2.60 - Bugfix: Opcode AFTEROVERLOAD does not have an argument that is a pin and needs to be initialized
|
// 5.2.60 - Bugfix: Opcode AFTEROVERLOAD does not have an argument that is a pin and needs to be initialized
|
||||||
// - Remove inrush throttle after half good time so that we go to mode overload if problem persists
|
// - Remove inrush throttle after half good time so that we go to mode overload if problem persists
|
||||||
// 5.2.59 - STM32 bugfix correct Serial1 definition for Nucleo-F401RE
|
// 5.2.59 - STM32 bugfix correct Serial1 definition for Nucleo-F401RE
|
||||||
|
|
Loading…
Reference in New Issue
Block a user