1
0
mirror of https://github.com/DCC-EX/CommandStation-EX.git synced 2024-11-27 18:16:13 +01:00

protect setSignal() changes in setDCSignal from being changed back during interrupt vis setDCCSignal

This commit is contained in:
Harald Barth 2022-06-06 23:03:27 +02:00
parent 2d52d88688
commit 79d6ab1c87
3 changed files with 50 additions and 14 deletions

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,16 +166,43 @@ 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("BrakePin=%d speedcode=%d"),brakePin,speedcode); 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();
fakePORTA=PORTA;
setSignal(tDir);
PORTA=fakePORTA;
interrupts();
} else if (HAVE_PORTB(fastSignalPin.shadowinout == &PORTB)) {
DIAG(F("setDCSignal: HAVEPORTB"));
noInterrupts();
fakePORTB=PORTB;
setSignal(tDir);
PORTB=fakePORTB;
interrupts();
} else if (HAVE_PORTC(fastSignalPin.shadowinout == &PORTC)) {
DIAG(F("setDCSignal: HAVEPORTC"));
noInterrupts();
fakePORTC=PORTC;
setSignal(tDir);
PORTC=fakePORTC;
interrupts();
}
}
} }
int MotorDriver::getCurrentRawInInterrupt() { int MotorDriver::getCurrentRawInInterrupt() {

View File

@ -66,12 +66,14 @@ 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

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,18 +124,15 @@ 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);
} }
@ -213,7 +216,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
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);
} }