1
0
mirror of https://github.com/DCC-EX/CommandStation-EX.git synced 2025-07-29 18:33:44 +02:00

Compare commits

...

7 Commits

Author SHA1 Message Date
Harald Barth
4e177cf744 make usePWM per track (trackPWM) 2nd half 2022-06-07 08:09:20 +02:00
Harald Barth
ff96ed1157 make usePWM per track (trackPWM) 2022-06-07 02:35:55 +02:00
Harald Barth
a363f37dc7 remember the base case 2022-06-07 00:17:46 +02:00
Harald Barth
11d959c8d0 make compile on Uno 2022-06-06 23:51:06 +02:00
Harald Barth
6ff5e7c7a8 tag version 2022-06-06 23:37:12 +02:00
Harald Barth
79d6ab1c87 protect setSignal() changes in setDCSignal from being changed back during interrupt vis setDCCSignal 2022-06-06 23:03:27 +02:00
Harald Barth
2d52d88688 enable more debug 2022-06-05 23:08:59 +02:00
4 changed files with 79 additions and 24 deletions

View File

@@ -1 +1 @@
#define GITHUB_SHA "TM-PORTX-20220605" #define GITHUB_SHA "TM-PORTX-20220607-1"

View File

@@ -41,16 +41,20 @@ MotorDriver::MotorDriver(VPIN power_pin, byte signal_pin, byte signal_pin2, int8
getFastPin(F("SIG"),signalPin,fastSignalPin); getFastPin(F("SIG"),signalPin,fastSignalPin);
pinMode(signalPin, OUTPUT); pinMode(signalPin, OUTPUT);
fastSignalPin.shadowinout = NULL;
if (HAVE_PORTA(fastSignalPin.inout == &PORTA)) { if (HAVE_PORTA(fastSignalPin.inout == &PORTA)) {
DIAG(F("Found PORTA pin %d"),signalPin); DIAG(F("Found PORTA pin %d"),signalPin);
fastSignalPin.shadowinout = fastSignalPin.inout;
fastSignalPin.inout = &fakePORTA; fastSignalPin.inout = &fakePORTA;
} }
if (HAVE_PORTB(fastSignalPin.inout == &PORTB)) { if (HAVE_PORTB(fastSignalPin.inout == &PORTB)) {
DIAG(F("Found PORTB pin %d"),signalPin); DIAG(F("Found PORTB pin %d"),signalPin);
fastSignalPin.shadowinout = fastSignalPin.inout;
fastSignalPin.inout = &fakePORTB; fastSignalPin.inout = &fakePORTB;
} }
if (HAVE_PORTC(fastSignalPin.inout == &PORTC)) { if (HAVE_PORTC(fastSignalPin.inout == &PORTC)) {
DIAG(F("Found PORTC pin %d"),signalPin); DIAG(F("Found PORTC pin %d"),signalPin);
fastSignalPin.shadowinout = fastSignalPin.inout;
fastSignalPin.inout = &fakePORTC; fastSignalPin.inout = &fakePORTC;
} }
@@ -162,15 +166,45 @@ int MotorDriver::getCurrentRaw() {
void MotorDriver::setDCSignal(byte speedcode) { void MotorDriver::setDCSignal(byte speedcode) {
if (brakePin == UNUSED_PIN) if (brakePin == UNUSED_PIN)
return; return;
// spedcoode is a dcc speed /direction // spedcoode is a dcc speed & direction
byte tSpeed=speedcode & 0x7F; byte tSpeed=speedcode & 0x7F; // DCC Speed with 0,1 stop and speed steps 2 to 127
// DCC Speed with 0,1 stop and speed steps 2 to 127 byte tDir=speedcode & 0x80;
byte brake; byte brake;
if (tSpeed <= 1) brake = 255; if (tSpeed <= 1) brake = 255;
else if (tSpeed >= 127) brake = 0; else if (tSpeed >= 127) brake = 0;
else brake = 2 * (128-tSpeed); else brake = 2 * (128-tSpeed);
DIAG(F("setDCSignal: speedcode=%d BrakePin=%d brake=%d dir=%d"),speedcode, brakePin, brake, tDir);
analogWrite(brakePin,brake); analogWrite(brakePin,brake);
setSignal(speedcode & 0x80); // as the port registers can be shadowed to get syncronized DCC signals
// we need to take care of that and we have to turn off interrupts during
// that time as otherwise setDCCSignal() which is called from interrupt
// contect can undo whatever we do here.
if (fastSignalPin.shadowinout != NULL) {
if (HAVE_PORTA(fastSignalPin.shadowinout == &PORTA)) {
DIAG(F("setDCSignal: HAVEPORTA"));
noInterrupts();
HAVE_PORTA(fakePORTA=PORTA);
setSignal(tDir);
HAVE_PORTA(PORTA=fakePORTA);
interrupts();
} else if (HAVE_PORTB(fastSignalPin.shadowinout == &PORTB)) {
DIAG(F("setDCSignal: HAVEPORTB"));
noInterrupts();
HAVE_PORTB(fakePORTB=PORTB);
setSignal(tDir);
HAVE_PORTB(PORTB=fakePORTB);
interrupts();
} else if (HAVE_PORTC(fastSignalPin.shadowinout == &PORTC)) {
DIAG(F("setDCSignal: HAVEPORTC"));
noInterrupts();
HAVE_PORTC(fakePORTC=PORTC);
setSignal(tDir);
HAVE_PORTC(PORTC=fakePORTC);
interrupts();
}
} else {
setSignal(tDir);
}
} }
int MotorDriver::getCurrentRawInInterrupt() { int MotorDriver::getCurrentRawInInterrupt() {

View File

@@ -2,6 +2,7 @@
* © 2021 Mike S * © 2021 Mike S
* © 2021 Fred Decker * © 2021 Fred Decker
* © 2020 Chris Harlow * © 2020 Chris Harlow
* © 2022 Harald Barth
* All rights reserved. * All rights reserved.
* *
* This file is part of Asbelos DCC API * This file is part of Asbelos DCC API
@@ -65,13 +66,15 @@
struct FASTPIN { struct FASTPIN {
volatile uint32_t *inout; volatile uint32_t *inout;
uint32_t maskHIGH; uint32_t maskHIGH;
uint32_t maskLOW; uint32_t maskLOW;
volatile uint32_t *shadowinout;
}; };
#else #else
struct FASTPIN { struct FASTPIN {
volatile uint8_t *inout; volatile uint8_t *inout;
uint8_t maskHIGH; uint8_t maskHIGH;
uint8_t maskLOW; uint8_t maskLOW;
volatile uint8_t *shadowinout;
}; };
#endif #endif
@@ -85,7 +88,7 @@ class MotorDriver {
virtual void setPower( POWERMODE mode); virtual void setPower( POWERMODE mode);
virtual POWERMODE getPower() { return powerMode;} virtual POWERMODE getPower() { return powerMode;}
__attribute__((always_inline)) inline void setSignal( bool high) { __attribute__((always_inline)) inline void setSignal( bool high) {
if (usePWM) { if (trackPWM) {
DCCTimer::setPWM(signalPin,high); DCCTimer::setPWM(signalPin,high);
} }
else { else {
@@ -119,7 +122,8 @@ class MotorDriver {
} }
bool isPWMCapable(); bool isPWMCapable();
bool canMeasureCurrent(); bool canMeasureCurrent();
static bool usePWM; bool trackPWM;
static bool usePWM; // TODO: Remove
static bool commonFaultPin; // This is a stupid motor shield which has only a common fault pin for both outputs static bool commonFaultPin; // This is a stupid motor shield which has only a common fault pin for both outputs
inline byte getFaultPin() { inline byte getFaultPin() {
return faultPin; return faultPin;

View File

@@ -87,11 +87,15 @@ void TrackManager::addTrack(byte t, MotorDriver* driver) {
} }
} }
// The port registers that are shadowing
// the real port registers. These are
// defined in Motordriver.cpp // defined in Motordriver.cpp
extern byte fakePORTA; extern byte fakePORTA;
extern byte fakePORTB; extern byte fakePORTB;
extern byte fakePORTC; extern byte fakePORTC;
// setDCCSignal(), called from interrupt context
// does assume ports are shadowed if they can be
void TrackManager::setDCCSignal( bool on) { void TrackManager::setDCCSignal( bool on) {
HAVE_PORTA(fakePORTA=PORTA); HAVE_PORTA(fakePORTA=PORTA);
HAVE_PORTB(fakePORTB=PORTB); HAVE_PORTB(fakePORTB=PORTB);
@@ -108,6 +112,8 @@ void TrackManager::setCutout( bool on) {
// TODO APPLY_BY_MODE(TRACK_MODE_MAIN,setCutout(on)); // TODO APPLY_BY_MODE(TRACK_MODE_MAIN,setCutout(on));
} }
// setPROGSignal(), called from interrupt context
// does assume ports are shadowed if they can be
void TrackManager::setPROGSignal( bool on) { void TrackManager::setPROGSignal( bool on) {
HAVE_PORTA(fakePORTA=PORTA); HAVE_PORTA(fakePORTA=PORTA);
HAVE_PORTB(fakePORTB=PORTB); HAVE_PORTB(fakePORTB=PORTB);
@@ -118,25 +124,22 @@ void TrackManager::setPROGSignal( bool on) {
HAVE_PORTC(PORTC=fakePORTC); HAVE_PORTC(PORTC=fakePORTC);
} }
// setDCSignal(), called from normal context
// MotorDriver::setDCSignal handles shadowed IO port changes.
// with interrupts turned off around the critical section
void TrackManager::setDCSignal(int16_t cab, byte speedbyte) { void TrackManager::setDCSignal(int16_t cab, byte speedbyte) {
HAVE_PORTA(fakePORTA=PORTA);
HAVE_PORTB(fakePORTB=PORTB);
HAVE_PORTC(fakePORTC=PORTC);
FOR_EACH_TRACK(t) { FOR_EACH_TRACK(t) {
if (trackDCAddr[t]!=cab) continue; if (trackDCAddr[t]!=cab) continue;
if (trackMode[t]==TRACK_MODE_DC) track[t]->setDCSignal(speedbyte); if (trackMode[t]==TRACK_MODE_DC) track[t]->setDCSignal(speedbyte);
else if (trackMode[t]==TRACK_MODE_DCX) track[t]->setDCSignal(speedbyte ^ 128); else if (trackMode[t]==TRACK_MODE_DCX) track[t]->setDCSignal(speedbyte ^ 128);
} }
HAVE_PORTA(PORTA=fakePORTA);
HAVE_PORTB(PORTB=fakePORTB);
HAVE_PORTC(PORTC=fakePORTC);
} }
bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr) { bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr) {
if (trackToSet>lastTrack || track[trackToSet]==NULL) return false; if (trackToSet>lastTrack || track[trackToSet]==NULL) return false;
//DIAG(F("Track=%c"),trackToSet+'A'); DIAG(F("Track=%c"),trackToSet+'A');
// DC tracks require a motorDriver that can set brake! // DC tracks require a motorDriver that can set brake!
if ((mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX) if ((mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX)
&& !track[trackToSet]->brakeCanPWM()) { && !track[trackToSet]->brakeCanPWM()) {
@@ -187,16 +190,30 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
// capable tracks is now DC or DCX. // capable tracks is now DC or DCX.
if (trackMode[t]==TRACK_MODE_DC || trackMode[t]==TRACK_MODE_DCX) { if (trackMode[t]==TRACK_MODE_DC || trackMode[t]==TRACK_MODE_DCX) {
if (track[t]->isPWMCapable()) { if (track[t]->isPWMCapable()) {
canDo=false; canDo=false; // this track is capable but can not run PWM
break; break; // in this mode, so abort and prevent globally below
} else {
track[t]->trackPWM=false; // this track sure can not run with PWM
DIAG(F("Track %c trackPWM 0 (not capable)"), t+'A');
} }
} else if (trackMode[t]==TRACK_MODE_MAIN || trackMode[t]==TRACK_MODE_PROG) } else if (trackMode[t]==TRACK_MODE_MAIN || trackMode[t]==TRACK_MODE_PROG) {
canDo &= track[t]->isPWMCapable(); track[t]->trackPWM = track[t]->isPWMCapable(); // trackPWM is still a guess here
DIAG(F("Track %c trackPWM %d"), t+'A', track[t]->trackPWM);
canDo &= track[t]->trackPWM;
}
} }
//DIAG(F("HAMode=%d"),canDo);
if (!canDo) { if (!canDo) {
DCCTimer::clearPWM(); // if we discover that HA mode was globally impossible
// we must adjust the trackPWM capabilities
FOR_EACH_TRACK(t) {
track[t]->trackPWM=false;
DIAG(F("Track %c trackPWM 0 (global override)"), t+'A');
}
DCCTimer::clearPWM(); // has to be AFTER trackPWM changes because if trackPWM==true this is undone for that track
} }
if (MotorDriver::usePWM != canDo)
DIAG(F("HA mode changed from %d to %d"), MotorDriver::usePWM, canDo);
MotorDriver::usePWM=canDo; MotorDriver::usePWM=canDo;
@@ -204,14 +221,14 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
track[trackToSet]->setPower( track[trackToSet]->setPower(
(mode==TRACK_MODE_MAIN || mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX || mode==TRACK_MODE_EXT) ? (mode==TRACK_MODE_MAIN || mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX || mode==TRACK_MODE_EXT) ?
mainPowerGuess : POWERMODE::OFF); mainPowerGuess : POWERMODE::OFF);
//DIAG(F("TrackMode=%d"),mode); DIAG(F("TrackMode=%d"),mode);
return true; return true;
} }
void TrackManager::applyDCSpeed(byte t) { void TrackManager::applyDCSpeed(byte t) {
uint8_t speedByte=DCC::getThrottleSpeedByte(trackDCAddr[t]); uint8_t speedByte=DCC::getThrottleSpeedByte(trackDCAddr[t]);
if (trackMode[t]==TRACK_MODE_DCX) if (trackMode[t]==TRACK_MODE_DCX)
speedByte = (speedByte & 0xF7) | ~(speedByte & 0x80); // Reverse highest bit speedByte = speedByte ^ 128; // reverse direction bit
track[t]->setDCSignal(speedByte); track[t]->setDCSignal(speedByte);
} }