mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-11-25 00:56:13 +01:00
Compare commits
No commits in common. "94648ead2852a124034c1419f8d8be1830e1ab16" and "6476a7aac20ca6f81dca428562a9c02b4b9fed31" have entirely different histories.
94648ead28
...
6476a7aac2
|
@ -180,8 +180,8 @@ void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
|
|||
return;
|
||||
}
|
||||
pin_to_channel[pin] = --cnt_channel;
|
||||
ledcSetup(cnt_channel, 1000, 8);
|
||||
ledcAttachPin(pin, cnt_channel);
|
||||
ledcSetup(cnt_channel, 1000, 8);
|
||||
} else {
|
||||
ledcAttachPin(pin, pin_to_channel[pin]);
|
||||
}
|
||||
|
|
|
@ -1 +1 @@
|
|||
#define GITHUB_SHA "devel-202307170030Z"
|
||||
#define GITHUB_SHA "devel-202307142111Z"
|
||||
|
|
|
@ -347,33 +347,7 @@ void MotorDriver::setDCSignal(byte speedcode) {
|
|||
interrupts();
|
||||
}
|
||||
}
|
||||
void MotorDriver::throttleInrush(bool on) {
|
||||
if (brakePin == UNUSED_PIN)
|
||||
return;
|
||||
byte duty = on ? 208 : 0;
|
||||
if (invertBrake)
|
||||
duty = 255-duty;
|
||||
#if defined(ARDUINO_ARCH_ESP32)
|
||||
if(on) {
|
||||
DCCTimer::DCCEXanalogWrite(brakePin,duty);
|
||||
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 62500);
|
||||
} else {
|
||||
ledcDetachPin(brakePin);
|
||||
}
|
||||
#else
|
||||
if(on){
|
||||
#if defined(ARDUINO_AVR_UNO)
|
||||
TCCR2B = (TCCR2B & B11111000) | B00000001; // div 1 is max
|
||||
#endif
|
||||
#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)
|
||||
TCCR2B = (TCCR2B & B11111000) | B00000001; // div 1 is max
|
||||
TCCR4B = (TCCR4B & B11111000) | B00000001; // div 1 is max
|
||||
TCCR5B = (TCCR5B & B11111000) | B00000001; // div 1 is max
|
||||
#endif
|
||||
}
|
||||
analogWrite(brakePin,duty);
|
||||
#endif
|
||||
}
|
||||
|
||||
unsigned int MotorDriver::raw2mA( int raw) {
|
||||
//DIAG(F("%d = %d * %d / %d"), (int32_t)raw * senseFactorInternal / senseScale, raw, senseFactorInternal, senseScale);
|
||||
return (int32_t)raw * senseFactorInternal / senseScale;
|
||||
|
@ -507,7 +481,11 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) {
|
|||
// check how long we have been in this state
|
||||
unsigned long mslpc = microsSinceLastPowerChange(POWERMODE::ALERT);
|
||||
if(checkFault()) {
|
||||
throttleInrush(true);
|
||||
#define INRUSH
|
||||
#ifdef INRUSH
|
||||
DCCTimer::DCCEXanalogWrite(brakePin,208);
|
||||
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 62500);
|
||||
#endif
|
||||
lastBadSample = now;
|
||||
unsigned long timeout = checkCurrent(useProgLimit) ? POWER_SAMPLE_IGNORE_FAULT_HIGH : POWER_SAMPLE_IGNORE_FAULT_LOW;
|
||||
if ( mslpc < timeout) {
|
||||
|
@ -516,7 +494,9 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) {
|
|||
break;
|
||||
}
|
||||
DIAG(F("TRACK %c FAULT PIN detected after %4M. Pause %4M)"), trackno + 'A', mslpc, power_sample_overload_wait);
|
||||
throttleInrush(false);
|
||||
#ifdef INRUSH
|
||||
DCCTimer::DCCEXanalogWrite(brakePin,0);
|
||||
#endif
|
||||
setPower(POWERMODE::OVERLOAD);
|
||||
break;
|
||||
}
|
||||
|
@ -533,7 +513,9 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) {
|
|||
unsigned int maxmA=raw2mA(tripValue);
|
||||
DIAG(F("TRACK %c POWER OVERLOAD %4dmA (max %4dmA) detected after %4M. Pause %4M"),
|
||||
trackno + 'A', mA, maxmA, mslpc, power_sample_overload_wait);
|
||||
throttleInrush(false);
|
||||
#ifdef INRUSH
|
||||
DCCTimer::DCCEXanalogWrite(brakePin,0);
|
||||
#endif
|
||||
setPower(POWERMODE::OVERLOAD);
|
||||
break;
|
||||
}
|
||||
|
@ -544,7 +526,9 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) {
|
|||
unsigned int mA=raw2mA(lastCurrent);
|
||||
DIAG(F("TRACK %c NORMAL (after %M/%M) %dmA"), trackno + 'A', goodtime, mslpc, mA);
|
||||
}
|
||||
throttleInrush(false);
|
||||
#ifdef INRUSH
|
||||
DCCTimer::DCCEXanalogWrite(brakePin,0);
|
||||
#endif
|
||||
setPower(POWERMODE::ON);
|
||||
}
|
||||
break;
|
||||
|
|
|
@ -27,10 +27,6 @@
|
|||
#include "IODevice.h"
|
||||
#include "DCCTimer.h"
|
||||
|
||||
// use powers of two so we can do logical and/or on the track modes in if clauses.
|
||||
enum TRACK_MODE : byte {TRACK_MODE_OFF = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PROG = 4,
|
||||
TRACK_MODE_DC = 8, TRACK_MODE_DCX = 16, TRACK_MODE_EXT = 32};
|
||||
|
||||
#define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH
|
||||
#define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW
|
||||
#define isHIGH(fastpin) (*fastpin.inout & fastpin.maskHIGH)
|
||||
|
@ -149,7 +145,6 @@ class MotorDriver {
|
|||
};
|
||||
inline pinpair getSignalPin() { return pinpair(signalPin,signalPin2); };
|
||||
void setDCSignal(byte speedByte);
|
||||
void throttleInrush(bool on);
|
||||
inline void detachDCSignal() {
|
||||
#if defined(__arm__)
|
||||
pinMode(brakePin, OUTPUT);
|
||||
|
@ -208,12 +203,6 @@ class MotorDriver {
|
|||
bool sampleCurrentFromHW();
|
||||
void startCurrentFromHW();
|
||||
#endif
|
||||
inline void setMode(TRACK_MODE m) {
|
||||
trackMode = m;
|
||||
};
|
||||
inline TRACK_MODE getMode() {
|
||||
return trackMode;
|
||||
};
|
||||
private:
|
||||
char trackLetter = '?';
|
||||
bool isProgTrack = false; // tells us if this is a prog track
|
||||
|
@ -290,7 +279,6 @@ class MotorDriver {
|
|||
static const int TRIP_CURRENT_PROG=250;
|
||||
unsigned long power_sample_overload_wait = POWER_SAMPLE_OVERLOAD_WAIT;
|
||||
unsigned int power_good_counter = 0;
|
||||
TRACK_MODE trackMode = TRACK_MODE_OFF; // we assume off at startup
|
||||
|
||||
};
|
||||
#endif
|
||||
|
|
|
@ -31,7 +31,7 @@
|
|||
|
||||
#define APPLY_BY_MODE(findmode,function) \
|
||||
FOR_EACH_TRACK(t) \
|
||||
if (track[t]->getMode()==findmode) \
|
||||
if (trackMode[t]==findmode) \
|
||||
track[t]->function;
|
||||
#ifndef DISABLE_PROG
|
||||
const int16_t HASH_KEYWORD_PROG = -29718;
|
||||
|
@ -44,6 +44,7 @@ const int16_t HASH_KEYWORD_EXT = 8201; // External DCC signal
|
|||
const int16_t HASH_KEYWORD_A = 65; // parser makes single chars the ascii.
|
||||
|
||||
MotorDriver * TrackManager::track[MAX_TRACKS];
|
||||
TRACK_MODE TrackManager::trackMode[MAX_TRACKS];
|
||||
int16_t TrackManager::trackDCAddr[MAX_TRACKS];
|
||||
|
||||
POWERMODE TrackManager::mainPowerGuess=POWERMODE::OFF;
|
||||
|
@ -73,7 +74,7 @@ void TrackManager::sampleCurrent() {
|
|||
waiting = false;
|
||||
tr++;
|
||||
if (tr > lastTrack) tr = 0;
|
||||
if (lastTrack < 2 || track[tr]->getMode() & TRACK_MODE_PROG) {
|
||||
if (lastTrack < 2 || trackMode[tr] & TRACK_MODE_PROG) {
|
||||
return; // We could continue but for prog track we
|
||||
// rather do it in next interrupt beacuse
|
||||
// that gives us well defined sampling point.
|
||||
|
@ -84,7 +85,7 @@ void TrackManager::sampleCurrent() {
|
|||
if (!waiting) {
|
||||
// look for a valid track to sample or until we are around
|
||||
while (true) {
|
||||
if (track[tr]->getMode() & ( TRACK_MODE_MAIN|TRACK_MODE_PROG|TRACK_MODE_DC|TRACK_MODE_DCX|TRACK_MODE_EXT )) {
|
||||
if (trackMode[tr] & ( TRACK_MODE_MAIN|TRACK_MODE_PROG|TRACK_MODE_DC|TRACK_MODE_DCX|TRACK_MODE_EXT )) {
|
||||
track[tr]->startCurrentFromHW();
|
||||
// for scope debug track[1]->setBrake(1);
|
||||
waiting = true;
|
||||
|
@ -137,10 +138,10 @@ void TrackManager::Setup(const FSH * shieldname,
|
|||
}
|
||||
|
||||
void TrackManager::addTrack(byte t, MotorDriver* driver) {
|
||||
trackMode[t]=TRACK_MODE_OFF;
|
||||
track[t]=driver;
|
||||
if (driver) {
|
||||
track[t]->setPower(POWERMODE::OFF);
|
||||
track[t]->setMode(TRACK_MODE_OFF);
|
||||
track[t]->setTrackLetter('A'+t);
|
||||
lastTrack=t;
|
||||
}
|
||||
|
@ -182,8 +183,8 @@ void TrackManager::setPROGSignal( bool on) {
|
|||
void TrackManager::setDCSignal(int16_t cab, byte speedbyte) {
|
||||
FOR_EACH_TRACK(t) {
|
||||
if (trackDCAddr[t]!=cab) continue;
|
||||
if (track[t]->getMode()==TRACK_MODE_DC) track[t]->setDCSignal(speedbyte);
|
||||
else if (track[t]->getMode()==TRACK_MODE_DCX) track[t]->setDCSignal(speedbyte ^ 128);
|
||||
if (trackMode[t]==TRACK_MODE_DC) track[t]->setDCSignal(speedbyte);
|
||||
else if (trackMode[t]==TRACK_MODE_DCX) track[t]->setDCSignal(speedbyte ^ 128);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -217,9 +218,9 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
|
|||
#endif
|
||||
// only allow 1 track to be prog
|
||||
FOR_EACH_TRACK(t)
|
||||
if (track[t]->getMode()==TRACK_MODE_PROG && t != trackToSet) {
|
||||
if (trackMode[t]==TRACK_MODE_PROG && t != trackToSet) {
|
||||
track[t]->setPower(POWERMODE::OFF);
|
||||
track[t]->setMode(TRACK_MODE_OFF);
|
||||
trackMode[t]=TRACK_MODE_OFF;
|
||||
track[t]->makeProgTrack(false); // revoke prog track special handling
|
||||
streamTrackState(NULL,t);
|
||||
}
|
||||
|
@ -227,7 +228,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
|
|||
} else {
|
||||
track[trackToSet]->makeProgTrack(false); // only the prog track knows it's type
|
||||
}
|
||||
track[trackToSet]->setMode(mode);
|
||||
trackMode[trackToSet]=mode;
|
||||
trackDCAddr[trackToSet]=dcAddr;
|
||||
streamTrackState(NULL,trackToSet);
|
||||
|
||||
|
@ -254,7 +255,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
|
|||
// DC tracks must not have the DCC PWM switched on
|
||||
// so we globally turn it off if one of the PWM
|
||||
// capable tracks is now DC or DCX.
|
||||
if (track[t]->getMode()==TRACK_MODE_DC || track[t]->getMode()==TRACK_MODE_DCX) {
|
||||
if (trackMode[t]==TRACK_MODE_DC || trackMode[t]==TRACK_MODE_DCX) {
|
||||
if (track[t]->isPWMCapable()) {
|
||||
canDo=false; // this track is capable but can not run PWM
|
||||
break; // in this mode, so abort and prevent globally below
|
||||
|
@ -262,7 +263,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
|
|||
track[t]->trackPWM=false; // this track sure can not run with PWM
|
||||
//DIAG(F("Track %c trackPWM 0 (not capable)"), t+'A');
|
||||
}
|
||||
} else if (track[t]->getMode()==TRACK_MODE_MAIN || track[t]->getMode()==TRACK_MODE_PROG) {
|
||||
} else if (trackMode[t]==TRACK_MODE_MAIN || trackMode[t]==TRACK_MODE_PROG) {
|
||||
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;
|
||||
|
@ -300,7 +301,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
|
|||
|
||||
void TrackManager::applyDCSpeed(byte t) {
|
||||
uint8_t speedByte=DCC::getThrottleSpeedByte(trackDCAddr[t]);
|
||||
if (track[t]->getMode()==TRACK_MODE_DCX)
|
||||
if (trackMode[t]==TRACK_MODE_DCX)
|
||||
speedByte = speedByte ^ 128; // reverse direction bit
|
||||
track[t]->setDCSignal(speedByte);
|
||||
}
|
||||
|
@ -346,7 +347,7 @@ void TrackManager::streamTrackState(Print* stream, byte t) {
|
|||
// null stream means send to commandDistributor for broadcast
|
||||
if (track[t]==NULL) return;
|
||||
auto format=F("");
|
||||
switch(track[t]->getMode()) {
|
||||
switch(trackMode[t]) {
|
||||
case TRACK_MODE_MAIN:
|
||||
format=F("<= %c MAIN>\n");
|
||||
break;
|
||||
|
@ -386,13 +387,13 @@ void TrackManager::loop() {
|
|||
if (nextCycleTrack>lastTrack) nextCycleTrack=0;
|
||||
if (track[nextCycleTrack]==NULL) return;
|
||||
MotorDriver * motorDriver=track[nextCycleTrack];
|
||||
bool useProgLimit=dontLimitProg? false: track[nextCycleTrack]->getMode()==TRACK_MODE_PROG;
|
||||
bool useProgLimit=dontLimitProg? false: trackMode[nextCycleTrack]==TRACK_MODE_PROG;
|
||||
motorDriver->checkPowerOverload(useProgLimit, nextCycleTrack);
|
||||
}
|
||||
|
||||
MotorDriver * TrackManager::getProgDriver() {
|
||||
FOR_EACH_TRACK(t)
|
||||
if (track[t]->getMode()==TRACK_MODE_PROG) return track[t];
|
||||
if (trackMode[t]==TRACK_MODE_PROG) return track[t];
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
@ -400,7 +401,7 @@ MotorDriver * TrackManager::getProgDriver() {
|
|||
std::vector<MotorDriver *>TrackManager::getMainDrivers() {
|
||||
std::vector<MotorDriver *> v;
|
||||
FOR_EACH_TRACK(t)
|
||||
if (track[t]->getMode()==TRACK_MODE_MAIN) v.push_back(track[t]);
|
||||
if (trackMode[t]==TRACK_MODE_MAIN) v.push_back(track[t]);
|
||||
return v;
|
||||
}
|
||||
#endif
|
||||
|
@ -410,7 +411,7 @@ void TrackManager::setPower2(bool setProg,POWERMODE mode) {
|
|||
FOR_EACH_TRACK(t) {
|
||||
MotorDriver * driver=track[t];
|
||||
if (!driver) continue;
|
||||
switch (track[t]->getMode()) {
|
||||
switch (trackMode[t]) {
|
||||
case TRACK_MODE_MAIN:
|
||||
if (setProg) break;
|
||||
// toggle brake before turning power on - resets overcurrent error
|
||||
|
@ -446,8 +447,8 @@ void TrackManager::setPower2(bool setProg,POWERMODE mode) {
|
|||
|
||||
POWERMODE TrackManager::getProgPower() {
|
||||
FOR_EACH_TRACK(t)
|
||||
if (track[t]->getMode()==TRACK_MODE_PROG)
|
||||
return track[t]->getPower();
|
||||
if (trackMode[t]==TRACK_MODE_PROG)
|
||||
return track[t]->getPower();
|
||||
return POWERMODE::OFF;
|
||||
}
|
||||
|
||||
|
@ -491,7 +492,7 @@ void TrackManager::setJoin(bool joined) {
|
|||
#ifdef ARDUINO_ARCH_ESP32
|
||||
if (joined) {
|
||||
FOR_EACH_TRACK(t) {
|
||||
if (track[t]->getMode()==TRACK_MODE_PROG) {
|
||||
if (trackMode[t]==TRACK_MODE_PROG) {
|
||||
tempProgTrack = t;
|
||||
setTrackMode(t, TRACK_MODE_MAIN);
|
||||
break;
|
||||
|
|
|
@ -27,6 +27,10 @@
|
|||
#include "MotorDriver.h"
|
||||
// Virtualised Motor shield multi-track hardware Interface
|
||||
|
||||
// use powers of two so we can do logical and/or on the track modes in if clauses.
|
||||
enum TRACK_MODE : byte {TRACK_MODE_OFF = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PROG = 4,
|
||||
TRACK_MODE_DC = 8, TRACK_MODE_DCX = 16, TRACK_MODE_EXT = 32};
|
||||
|
||||
// These constants help EXRAIL macros say SET_TRACK(2,mode) OR SET_TRACK(C,mode) etc.
|
||||
const byte TRACK_NUMBER_0=0, TRACK_NUMBER_A=0;
|
||||
const byte TRACK_NUMBER_1=1, TRACK_NUMBER_B=1;
|
||||
|
@ -96,6 +100,7 @@ class TrackManager {
|
|||
static POWERMODE mainPowerGuess;
|
||||
static void applyDCSpeed(byte t);
|
||||
|
||||
static TRACK_MODE trackMode[MAX_TRACKS];
|
||||
static int16_t trackDCAddr[MAX_TRACKS]; // dc address if TRACK_MODE_DC or TRACK_MODE_DCX
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
static byte tempProgTrack; // holds the prog track number during join
|
||||
|
|
Loading…
Reference in New Issue
Block a user