mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-11-22 23:56:13 +01:00
Compare commits
16 Commits
61a116e2af
...
84ca14428f
Author | SHA1 | Date | |
---|---|---|---|
|
84ca14428f | ||
|
ed853eef1d | ||
|
05e77c924e | ||
|
c5c5609fc6 | ||
|
9c263062e4 | ||
|
f39fd89fbd | ||
|
4e57a80265 | ||
|
27dc8059d7 | ||
|
dc2eae499f | ||
|
c518dcdc0b | ||
|
e6047f6693 | ||
|
96c4757cc6 | ||
|
5d411e6a08 | ||
|
7bd1bae470 | ||
|
7cc3cf9c65 | ||
|
2738d86431 |
|
@ -209,7 +209,7 @@ int16_t CommandDistributor::retClockTime() {
|
|||
|
||||
void CommandDistributor::broadcastLoco(byte slot) {
|
||||
DCC::LOCO * sp=&DCC::speedTable[slot];
|
||||
broadcastReply(COMMAND_TYPE, F("<l %d %d %d %L>\n"), sp->loco,slot,sp->speedCode,sp->functions);
|
||||
broadcastReply(COMMAND_TYPE, F("<l %d %d %d %l>\n"), sp->loco,slot,sp->speedCode,sp->functions);
|
||||
#ifdef SABERTOOTH
|
||||
if (Serial2 && sp->loco == SABERTOOTH) {
|
||||
static uint8_t rampingmode = 0;
|
||||
|
@ -248,6 +248,10 @@ void CommandDistributor::broadcastLoco(byte slot) {
|
|||
#endif
|
||||
}
|
||||
|
||||
void CommandDistributor::broadcastForgetLoco(int16_t loco) {
|
||||
broadcastReply(COMMAND_TYPE, F("<l %d 0 1 0>\n<- %d>\n"), loco,loco);
|
||||
}
|
||||
|
||||
void CommandDistributor::broadcastPower() {
|
||||
char pstr[] = "? x";
|
||||
for(byte t=0; t<TrackManager::MAX_TRACKS; t++)
|
||||
|
|
|
@ -47,6 +47,7 @@ private:
|
|||
public :
|
||||
static void parse(byte clientId,byte* buffer, RingStream * ring);
|
||||
static void broadcastLoco(byte slot);
|
||||
static void broadcastForgetLoco(int16_t loco);
|
||||
static void broadcastSensor(int16_t id, bool value);
|
||||
static void broadcastTurnout(int16_t id, bool isClosed);
|
||||
static void broadcastTurntable(int16_t id, uint8_t position, bool moving);
|
||||
|
|
6
DCC.cpp
6
DCC.cpp
|
@ -742,11 +742,15 @@ void DCC::forgetLoco(int cab) { // removes any speed reminders for this loco
|
|||
if (reg>=0) {
|
||||
speedTable[reg].loco=0;
|
||||
setThrottle2(cab,1); // ESTOP if this loco still on track
|
||||
CommandDistributor::broadcastForgetLoco(cab);
|
||||
}
|
||||
}
|
||||
void DCC::forgetAllLocos() { // removes all speed reminders
|
||||
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;
|
||||
|
|
|
@ -817,7 +817,9 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
|
|||
CommandDistributor::setVirtualLCDSerial(stream);
|
||||
StringFormatter::send(stream,
|
||||
F("<@ 0 0 \"DCC-EX v" VERSION "\">\n"
|
||||
"<@ 0 1 \"Lic GPLv3\">\n"));
|
||||
"<@ 0 1 \"Lic GPLv3 \">\n"
|
||||
"<@ 0 8 \"Powered by DCC-EX \">\n"
|
||||
CommandDistributor::setVirtualLCDSerial(NULL);
|
||||
return;
|
||||
#endif
|
||||
default: //anything else will diagnose and drop out to <X>
|
||||
|
|
|
@ -628,14 +628,16 @@ void RMFT2::loop2() {
|
|||
skipIf=blinkState!=at_timeout;
|
||||
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)) {
|
||||
// reset timer to half a second and keep waiting
|
||||
// reset timer and keep waiting
|
||||
waitAfter=millis();
|
||||
delayMe(50);
|
||||
return;
|
||||
}
|
||||
if (millis()-waitAfter < 500 ) return;
|
||||
if (millis()-waitAfter < getOperand(1) ) return;
|
||||
break;
|
||||
|
||||
case OPCODE_AFTEROVERLOAD: // waits for the power to be turned back on - either by power routine or button
|
||||
|
|
|
@ -195,7 +195,7 @@
|
|||
#ifndef RMFT2_UNDEF_ONLY
|
||||
#define ACTIVATE(addr,subaddr)
|
||||
#define ACTIVATEL(addr)
|
||||
#define AFTER(sensor_id)
|
||||
#define AFTER(sensor_id,timer...)
|
||||
#define AFTEROVERLOAD(track_id)
|
||||
#define ALIAS(name,value...)
|
||||
#define AMBER(signal_id)
|
||||
|
|
|
@ -463,7 +463,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
|
|||
|
||||
#define ACTIVATE(addr,subaddr) OPCODE_DCCACTIVATE,V(addr<<3 | subaddr<<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 ALIAS(name,value...)
|
||||
#define AMBER(signal_id) OPCODE_AMBER,V(signal_id),
|
||||
|
|
|
@ -1 +1 @@
|
|||
#define GITHUB_SHA "devel-202406182019Z"
|
||||
#define GITHUB_SHA "devel-202408080849Z"
|
||||
|
|
|
@ -547,6 +547,6 @@ protected:
|
|||
#include "IO_duinoNodes.h"
|
||||
#include "IO_EXIOExpander.h"
|
||||
#include "IO_trainbrains.h"
|
||||
|
||||
#include "IO_EncoderThrottle.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
|
||||
* © 2024 Herb Morton
|
||||
* © 2021 Mike S
|
||||
* © 2021 Fred Decker
|
||||
* © 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)) {
|
||||
DIAG(F("Found PORTH pin %d"),signalPin);
|
||||
fastSignalPin.shadowinout = fastSignalPin.inout;
|
||||
fastSignalPin.inout = &shadowPORTF;
|
||||
fastSignalPin.inout = &shadowPORTH;
|
||||
}
|
||||
|
||||
signalPin2=signal_pin2;
|
||||
|
|
|
@ -1,6 +1,8 @@
|
|||
/*
|
||||
* © 2022 Chris Harlow
|
||||
* © 2022-2024 Harald Barth
|
||||
* © 2023-2024 Paul M. Antoine
|
||||
* © 2024 Herb Morton
|
||||
* © 2023 Colin Murdoch
|
||||
* All rights reserved.
|
||||
*
|
||||
|
@ -149,6 +151,8 @@ void TrackManager::setDCCSignal( bool on) {
|
|||
HAVE_PORTD(shadowPORTD=PORTD);
|
||||
HAVE_PORTE(shadowPORTE=PORTE);
|
||||
HAVE_PORTF(shadowPORTF=PORTF);
|
||||
HAVE_PORTG(shadowPORTF=PORTG);
|
||||
HAVE_PORTH(shadowPORTF=PORTH);
|
||||
APPLY_BY_MODE(TRACK_MODE_MAIN,setSignal(on));
|
||||
HAVE_PORTA(PORTA=shadowPORTA);
|
||||
HAVE_PORTB(PORTB=shadowPORTB);
|
||||
|
@ -156,6 +160,8 @@ void TrackManager::setDCCSignal( bool on) {
|
|||
HAVE_PORTD(PORTD=shadowPORTD);
|
||||
HAVE_PORTE(PORTE=shadowPORTE);
|
||||
HAVE_PORTF(PORTF=shadowPORTF);
|
||||
HAVE_PORTG(shadowPORTF=PORTG);
|
||||
HAVE_PORTH(shadowPORTF=PORTH);
|
||||
}
|
||||
|
||||
// setPROGSignal(), called from interrupt context
|
||||
|
@ -167,6 +173,8 @@ void TrackManager::setPROGSignal( bool on) {
|
|||
HAVE_PORTD(shadowPORTD=PORTD);
|
||||
HAVE_PORTE(shadowPORTE=PORTE);
|
||||
HAVE_PORTF(shadowPORTF=PORTF);
|
||||
HAVE_PORTG(shadowPORTF=PORTG);
|
||||
HAVE_PORTH(shadowPORTF=PORTH);
|
||||
APPLY_BY_MODE(TRACK_MODE_PROG,setSignal(on));
|
||||
HAVE_PORTA(PORTA=shadowPORTA);
|
||||
HAVE_PORTB(PORTB=shadowPORTB);
|
||||
|
@ -174,6 +182,8 @@ void TrackManager::setPROGSignal( bool on) {
|
|||
HAVE_PORTD(PORTD=shadowPORTD);
|
||||
HAVE_PORTE(PORTE=shadowPORTE);
|
||||
HAVE_PORTF(PORTF=shadowPORTF);
|
||||
HAVE_PORTG(shadowPORTF=PORTG);
|
||||
HAVE_PORTH(shadowPORTF=PORTH);
|
||||
}
|
||||
|
||||
// setDCSignal(), called from normal context
|
||||
|
@ -631,23 +641,25 @@ void TrackManager::setJoinRelayPin(byte joinRelayPin) {
|
|||
|
||||
void TrackManager::setJoin(bool joined) {
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
if (joined) {
|
||||
if (joined) { // if we go into joined mode (PROG acts as MAIN)
|
||||
FOR_EACH_TRACK(t) {
|
||||
if (track[t]->getMode() & TRACK_MODE_PROG) {
|
||||
tempProgTrack = t;
|
||||
if (track[t]->getMode() & TRACK_MODE_PROG) { // find PROG track
|
||||
tempProgTrack = t; // remember PROG track
|
||||
setTrackMode(t, TRACK_MODE_MAIN);
|
||||
break;
|
||||
track[t]->setPower(POWERMODE::ON); // if joined, always on
|
||||
break; // there is only one prog track, done
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if (tempProgTrack != MAX_TRACKS+1) {
|
||||
// as setTrackMode with TRACK_MODE_PROG defaults to
|
||||
// power off, we will take the current power state
|
||||
// of our track and then preserve that state.
|
||||
POWERMODE tPTmode = track[tempProgTrack]->getPower(); //get current power status of this track
|
||||
setTrackMode(tempProgTrack, TRACK_MODE_PROG);
|
||||
track[tempProgTrack]->setPower(tPTmode); //set track status as it was before
|
||||
// setTrackMode defaults to power off, so we
|
||||
// need to preserve that state.
|
||||
POWERMODE tPTmode = track[tempProgTrack]->getPower(); // get current power status of this track
|
||||
setTrackMode(tempProgTrack, TRACK_MODE_PROG); // set track mode back to prog
|
||||
track[tempProgTrack]->setPower(tPTmode); // set power status as it was before
|
||||
tempProgTrack = MAX_TRACKS+1;
|
||||
} else {
|
||||
DIAG(F("Unjoin but no remembered prog track"));
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
14
version.h
14
version.h
|
@ -3,7 +3,19 @@
|
|||
|
||||
#include "StringFormatter.h"
|
||||
|
||||
#define VERSION "5.2.66"
|
||||
#define VERSION "5.2.74"
|
||||
// 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
|
||||
|
|
Loading…
Reference in New Issue
Block a user