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

Merge branch 'DCdistrict' into EX-RAIL-DC

This commit is contained in:
Harald Barth 2021-09-04 09:09:05 +02:00
commit faa8383bc3
6 changed files with 76 additions and 7 deletions

14
DCC.cpp
View File

@ -61,8 +61,15 @@ void DCC::begin(const FSH * motorShieldName, MotorDriver * mainDriver, MotorDriv
EEStore::init(); EEStore::init();
DCCWaveform::begin(mainDriver,progDriver); DCCWaveform::begin(mainDriver,progDriver);
#ifdef DCdistrict
DCCWaveform::mainTrack.pwmSpeed(0);
#else
DCCWaveform::mainTrack.pwmSpeed(255);
#endif
DCCWaveform::progTrack.pwmSpeed(255);
} }
void DCC::setJoinRelayPin(byte joinRelayPin) { void DCC::setJoinRelayPin(byte joinRelayPin) {
joinRelay=joinRelayPin; joinRelay=joinRelayPin;
if (joinRelay!=UNUSED_PIN) { if (joinRelay!=UNUSED_PIN) {
@ -72,6 +79,13 @@ void DCC::setJoinRelayPin(byte joinRelayPin) {
} }
void DCC::setThrottle( uint16_t cab, uint8_t tSpeed, bool tDirection) { void DCC::setThrottle( uint16_t cab, uint8_t tSpeed, bool tDirection) {
#ifdef DCdistrict
if (cab == DCdistrict) {
DCCWaveform::mainTrack.pwmSpeed(tSpeed, tDirection);
}
#else
#error fooar
#endif
byte speedCode = (tSpeed & 0x7F) + tDirection * 128; byte speedCode = (tSpeed & 0x7F) + tDirection * 128;
setThrottle2(cab, speedCode); setThrottle2(cab, speedCode);
// retain speed for loco reminders // retain speed for loco reminders

View File

@ -65,7 +65,9 @@ void DCCWaveform::interruptHandler() {
byte sigProg=progTrackSyncMain? sigMain : signalTransform[progTrack.state]; byte sigProg=progTrackSyncMain? sigMain : signalTransform[progTrack.state];
// Set the signal state for both tracks // Set the signal state for both tracks
#ifndef DCdistrict
mainTrack.motorDriver->setSignal(sigMain); mainTrack.motorDriver->setSignal(sigMain);
#endif
progTrack.motorDriver->setSignal(sigProg); progTrack.motorDriver->setSignal(sigProg);
// Move on in the state engine // Move on in the state engine

View File

@ -107,6 +107,27 @@ class DCCWaveform {
inline void setMaxAckPulseDuration(unsigned int i) { inline void setMaxAckPulseDuration(unsigned int i) {
maxAckPulseDuration = i; maxAckPulseDuration = i;
} }
#ifdef DCdistrict
inline void pwmSpeed(uint8_t tSpeed) {
// DCC Speed with 0,1 stop and speed steps 2 to 127
uint8_t brake;
if (!motorDriver)
return;
if (tSpeed <= 1)
brake = 255;
else if (tSpeed >= 127)
brake = 0;
else
brake = 2 * (128-tSpeed);
motorDriver->setBrake(brake);
}
inline void pwmSpeed(uint8_t tSpeed, bool tDirection) {
if (!motorDriver)
return;
pwmSpeed(tSpeed);
motorDriver->setSignal(tDirection);
}
#endif
private: private:

View File

@ -31,6 +31,7 @@ bool MotorDriver::commonFaultPin=false;
MotorDriver::MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, int8_t brake_pin, MotorDriver::MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, int8_t brake_pin,
byte current_pin, float sense_factor, unsigned int trip_milliamps, byte fault_pin) { byte current_pin, float sense_factor, unsigned int trip_milliamps, byte fault_pin) {
brakePWM=false;
powerPin=power_pin; powerPin=power_pin;
getFastPin(F("POWER"),powerPin,fastPowerPin); getFastPin(F("POWER"),powerPin,fastPowerPin);
pinMode(powerPin, OUTPUT); pinMode(powerPin, OUTPUT);
@ -53,7 +54,7 @@ MotorDriver::MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, int8
brakePin=invertBrake ? 0-brake_pin : brake_pin; brakePin=invertBrake ? 0-brake_pin : brake_pin;
getFastPin(F("BRAKE"),brakePin,fastBrakePin); getFastPin(F("BRAKE"),brakePin,fastBrakePin);
pinMode(brakePin, OUTPUT); pinMode(brakePin, OUTPUT);
setBrake(false); // setBrake(0); moved out to DCC::begin
} }
else brakePin=UNUSED_PIN; else brakePin=UNUSED_PIN;
@ -89,8 +90,11 @@ void MotorDriver::setPower(bool on) {
if (on) { if (on) {
// toggle brake before turning power on - resets overcurrent error // toggle brake before turning power on - resets overcurrent error
// on the Pololu board if brake is wired to ^D2. // on the Pololu board if brake is wired to ^D2.
setBrake(true); // Yes, this is an ugly special case
setBrake(false); if (brakePin == 4 && invertBrake) {
setBrake(255);
setBrake(0);
}
setHIGH(fastPowerPin); setHIGH(fastPowerPin);
} }
else setLOW(fastPowerPin); else setLOW(fastPowerPin);
@ -104,10 +108,29 @@ void MotorDriver::setPower(bool on) {
// (HIGH == release brake) and setBrake does // (HIGH == release brake) and setBrake does
// compensate for that. // compensate for that.
// //
void MotorDriver::setBrake(bool on) { void MotorDriver::setBrake(uint8_t intensity) {
if (brakePin == UNUSED_PIN) return; if (brakePin == UNUSED_PIN) return;
if (on ^ invertBrake) setHIGH(fastBrakePin); DIAG(F("Brake pin=%d val=%d"),brakePin,intensity);
else setLOW(fastBrakePin); if (invertBrake)
intensity = 255 - intensity;
if (intensity == 255) {
if (brakePWM) {
digitalWrite(brakePin, HIGH);
brakePWM = false;
} else
setHIGH(fastBrakePin);
return;
}
if (intensity == 0) {
if (brakePWM) {
digitalWrite(brakePin, LOW);
brakePWM = false;
} else
setLOW(fastBrakePin);
return;
}
brakePWM = true;
analogWrite(brakePin, intensity);
} }
void MotorDriver::setSignal( bool high) { void MotorDriver::setSignal( bool high) {

View File

@ -46,7 +46,7 @@ class MotorDriver {
byte current_pin, float senseFactor, unsigned int tripMilliamps, byte faultPin); byte current_pin, float senseFactor, unsigned int tripMilliamps, byte faultPin);
virtual void setPower( bool on); virtual void setPower( bool on);
virtual void setSignal( bool high); virtual void setSignal( bool high);
virtual void setBrake( bool on); virtual void setBrake(uint8_t);
virtual int getCurrentRaw(); virtual int getCurrentRaw();
virtual unsigned int raw2mA( int raw); virtual unsigned int raw2mA( int raw);
virtual int mA2raw( unsigned int mA); virtual int mA2raw( unsigned int mA);
@ -69,6 +69,7 @@ class MotorDriver {
FASTPIN fastPowerPin,fastSignalPin, fastSignalPin2, fastBrakePin,fastFaultPin; FASTPIN fastPowerPin,fastSignalPin, fastSignalPin2, fastBrakePin,fastFaultPin;
bool dualSignal; // true to use signalPin2 bool dualSignal; // true to use signalPin2
bool invertBrake; // brake pin passed as negative means pin is inverted bool invertBrake; // brake pin passed as negative means pin is inverted
bool brakePWM; // brake is used for PWM
float senseFactor; float senseFactor;
int senseOffset; int senseOffset;
unsigned int tripMilliamps; unsigned int tripMilliamps;

View File

@ -23,6 +23,14 @@ The configuration file for DCC-EX Command Station
**********************************************************************/ **********************************************************************/
// TO GET THE DC district feature put this in your config.h:
//
//#define BRAKE_MOTOR_SHIELD F("BRAKE_MOTOR_SHIELD"), \
// new MotorDriver(3, 12, UNUSED_PIN, 9, A0, 2.99, 2000, UNUSED_PIN), \
// new MotorDriver(11, 13, UNUSED_PIN, UNUSED_PIN, A1, 2.99, 2000, UNUSED_PIN)
//#define MOTOR_SHIELD_TYPE BRAKE_MOTOR_SHIELD
//#define DCdistrict 2
///////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////
// NOTE: Before connecting these boards and selecting one in this software // NOTE: Before connecting these boards and selecting one in this software
// check the quick install guides!!! Some of these boards require a voltage // check the quick install guides!!! Some of these boards require a voltage