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

Compare commits

...

3 Commits

Author SHA1 Message Date
Harald Barth
802f9c96b4 DC via power pin 3rd part 2023-02-13 20:48:48 +01:00
Harald Barth
0e36b3b997 DC via power pin 2nd part 2023-02-13 17:06:33 +01:00
Harald Barth
9482041799 DC via power pin 1st try 2023-02-12 23:31:13 +01:00
4 changed files with 63 additions and 29 deletions

View File

@@ -1 +1 @@
#define GITHUB_SHA "devel-202302121935Z" #define GITHUB_SHA "devel-202302131946Z"

View File

@@ -85,7 +85,6 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
getFastPin(F("BRAKE"),brakePin,fastBrakePin); getFastPin(F("BRAKE"),brakePin,fastBrakePin);
// if brake is used for railcom cutout we need to do PORTX register trick here as well // if brake is used for railcom cutout we need to do PORTX register trick here as well
pinMode(brakePin, OUTPUT); pinMode(brakePin, OUTPUT);
setBrake(true); // start with brake on in case we hace DC stuff going on
} }
else brakePin=UNUSED_PIN; else brakePin=UNUSED_PIN;
@@ -147,6 +146,8 @@ void MotorDriver::setPower(POWERMODE mode) {
noInterrupts(); noInterrupts();
IODevice::write(powerPin,invertPower ? LOW : HIGH); IODevice::write(powerPin,invertPower ? LOW : HIGH);
interrupts(); interrupts();
if (DCinuse)
setDCSignal(curSpeedCode);
if (isProgTrack) if (isProgTrack)
DCCWaveform::progTrack.clearResets(); DCCWaveform::progTrack.clearResets();
} }
@@ -154,6 +155,13 @@ void MotorDriver::setPower(POWERMODE mode) {
noInterrupts(); noInterrupts();
IODevice::write(powerPin,invertPower ? HIGH : LOW); IODevice::write(powerPin,invertPower ? HIGH : LOW);
interrupts(); interrupts();
if (DCinuse) {
// remember current (DC) speed
// but set PWM to zero/stop
byte s = curSpeedCode;
setDCSignal(128);
curSpeedCode = s;
}
} }
powerMode=mode; powerMode=mode;
} }
@@ -238,26 +246,51 @@ void MotorDriver::startCurrentFromHW() {
#if defined(ARDUINO_ARCH_ESP32) #if defined(ARDUINO_ARCH_ESP32)
uint16_t taurustones[28] = { 165, 175, 196, 220, uint16_t taurustones[28] = { 165, 175, 196, 220,
247, 262, 294, 330, 247, 262, 294, 330,
249, 392, 440, 494, 349, 392, 440, 494,
523, 587, 659, 698, 523, 587, 659, 698,
494, 440, 392, 249, 494, 440, 392, 249,
330, 284, 262, 247, 330, 284, 262, 247,
220, 196, 175, 165 }; 220, 196, 175, 165 };
#endif #endif
void MotorDriver::setDCSignal(byte speedcode) { void MotorDriver::setDCSignal(byte speedcode) {
if (brakePin == UNUSED_PIN) curSpeedCode = speedcode;
return; DCinuse = true;
#if defined(ARDUINO_AVR_UNO) #if defined(ARDUINO_AVR_UNO)
TCCR2B = (TCCR2B & B11111000) | B00000110; // set divisor on timer 2 to result in (approx) 122.55Hz if (powerPin == 3 || powerPin == 11)
TCCR2B = (TCCR2B & B11111000) | B00000110; // D3, D11: set divisor on timer 2 to result in (approx) 122.55Hz
#endif #endif
#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560) #if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)
TCCR2B = (TCCR2B & B11111000) | B00000110; // set divisor on timer 2 to result in (approx) 122.55Hz // As timer 0 is the system timer, we leave it alone
TCCR4B = (TCCR4B & B11111000) | B00000100; // same for timer 4 but maxcount and thus divisor differs //TCCR0B = (TCCR0B & B11111000) | B00000100; // D4, D13 : 122 or 244Hz?
// As we use timer 1 for DCC we leave it alone
//TCCR1B = (TCCR1B & B11111000) | B00000100; // D11, D12 : 122Hz
switch(powerPin) {
case 9:
case 10:
TCCR2B = (TCCR2B & B11111000) | B00000110; // D9, D10 : 122Hz
break;
case 2:
case 3:
case 5:
TCCR3B = (TCCR3B & B11111000) | B00000100; // D2, D3, D5 : 122Hz but maxcount and thus divisor differs
break;
case 6:
case 7:
case 8:
TCCR4B = (TCCR4B & B11111000) | B00000100; // D6, D7, D8 : 122Hz but maxcount and thus divisor differs
break;
case 44:
case 45:
case 46:
TCCR5B = (TCCR5B & B11111000) | B00000100; // D44,D45,D46: 122Hz but maxcount and thus divisor differs
break;
}
#endif #endif
// spedcoode is a dcc speed & direction // spedcoode is a dcc speed & direction
byte tSpeed=speedcode & 0x7F; // DCC Speed with 0,1 stop and speed steps 2 to 127 byte tSpeed=speedcode & 0x7F; // DCC Speed with 0,1 stop and speed steps 2 to 127
byte tDir=speedcode & 0x80; byte tDir=speedcode & 0x80;
byte brake; byte pwmratio;
#if defined(ARDUINO_ARCH_ESP32) #if defined(ARDUINO_ARCH_ESP32)
{ {
int f = 131; int f = 131;
@@ -266,18 +299,18 @@ void MotorDriver::setDCSignal(byte speedcode) {
f = taurustones[ (tSpeed-2)/2 ] ; f = taurustones[ (tSpeed-2)/2 ] ;
} }
} }
DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup DCCEXanalogWriteFrequency(powerPin, f); // set DC PWM frequency to 100Hz XXX May move to setup
} }
#endif #endif
if (tSpeed <= 1) brake = 255; if (tSpeed <= 1) pwmratio = 0;
else if (tSpeed >= 127) brake = 0; else if (tSpeed >= 127) pwmratio = 255;
else brake = 2 * (128-tSpeed); else pwmratio = 2 * tSpeed;
if (invertBrake) if (invertPower)
brake=255-brake; pwmratio =255-pwmratio;
#if defined(ARDUINO_ARCH_ESP32) #if defined(ARDUINO_ARCH_ESP32)
DCCEXanalogWrite(brakePin,brake); DCCEXanalogWrite(powerPin,pwmratio);
#else #else
analogWrite(brakePin,brake); analogWrite(powerPin,pwmratio);
#endif #endif
//DIAG(F("DCSignal %d"), speedcode); //DIAG(F("DCSignal %d"), speedcode);
if (HAVE_PORTA(fastSignalPin.shadowinout == &PORTA)) { if (HAVE_PORTA(fastSignalPin.shadowinout == &PORTA)) {

View File

@@ -146,25 +146,27 @@ class MotorDriver {
void setDCSignal(byte speedByte); void setDCSignal(byte speedByte);
inline void detachDCSignal() { inline void detachDCSignal() {
#if defined(__arm__) #if defined(__arm__)
pinMode(brakePin, OUTPUT); pinMode(powerPin, OUTPUT);
#elif defined(ARDUINO_ARCH_ESP32) #elif defined(ARDUINO_ARCH_ESP32)
ledcDetachPin(brakePin); ledcDetachPin(powerPin);
#else #else
setDCSignal(128); setDCSignal(128);
#endif #endif
DCinuse = false;
}; };
int getCurrentRaw(bool fromISR=false); int getCurrentRaw(bool fromISR=false);
unsigned int raw2mA( int raw); unsigned int raw2mA( int raw);
unsigned int mA2raw( unsigned int mA); unsigned int mA2raw( unsigned int mA);
inline bool brakeCanPWM() { inline bool powerPinCanPWM() {
#if defined(ARDUINO_ARCH_ESP32) || defined(__arm__) #if defined(ARDUINO_ARCH_ESP32) || defined(__arm__)
// TODO: on ARM we can use digitalPinHasPWM, and may wish/need to // TODO: on ARM we can use digitalPinHasPWM, and may wish/need to
return true; return true;
#else #else
#ifdef digitalPinToTimer #ifdef digitalPinHasPWM
return ((brakePin!=UNUSED_PIN) && (digitalPinToTimer(brakePin))); return digitalPinHasPWM(powerPin);
#else #else
return (brakePin<14 && brakePin >1); #warning No good digitalPinHasPWM doing approximation
return (powerPin<14 && powerPin >1);
#endif //digitalPinToTimer #endif //digitalPinToTimer
#endif //ESP32/ARM #endif //ESP32/ARM
} }
@@ -232,6 +234,7 @@ class MotorDriver {
static const int TRIP_CURRENT_PROG=250; static const int TRIP_CURRENT_PROG=250;
unsigned long power_sample_overload_wait = POWER_SAMPLE_OVERLOAD_WAIT; unsigned long power_sample_overload_wait = POWER_SAMPLE_OVERLOAD_WAIT;
unsigned int power_good_counter = 0; unsigned int power_good_counter = 0;
bool DCinuse = false;
byte curSpeedCode = 0;
}; };
#endif #endif

View File

@@ -177,10 +177,10 @@ 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 power pin PWM
if ((mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX) if ((mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX)
&& !track[trackToSet]->brakeCanPWM()) { && !track[trackToSet]->powerPinCanPWM()) {
DIAG(F("Brake pin can't PWM: No DC")); DIAG(F("Power pin can't PWM: No DC"));
return false; return false;
} }
@@ -218,7 +218,6 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
if (!(mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX)) { if (!(mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX)) {
// DCC tracks need to have set the PWM to zero or they will not work. // DCC tracks need to have set the PWM to zero or they will not work.
track[trackToSet]->detachDCSignal(); track[trackToSet]->detachDCSignal();
track[trackToSet]->setBrake(false);
} }
// EXT is a special case where the signal pin is // EXT is a special case where the signal pin is
@@ -396,7 +395,6 @@ void TrackManager::setPower2(bool setProg,POWERMODE mode) {
case TRACK_MODE_DC: case TRACK_MODE_DC:
case TRACK_MODE_DCX: case TRACK_MODE_DCX:
if (setProg) break; if (setProg) break;
driver->setBrake(true); // DC starts with brake on
applyDCSpeed(t); // speed match DCC throttles applyDCSpeed(t); // speed match DCC throttles
driver->setPower(mode); driver->setPower(mode);
break; break;