mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-11-23 08:06:13 +01:00
DCdistrict prototypr
This commit is contained in:
parent
b47d768de2
commit
fafa9d8477
22
DCC.cpp
22
DCC.cpp
|
@ -57,8 +57,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.motorDriver->setBrake(255);
|
||||||
|
#else
|
||||||
|
DCCWaveform::mainTrack.motorDriver->setBrake(0);
|
||||||
|
#endif
|
||||||
|
DCCWaveform::progTrack.motorDriver->setBrake(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void DCC::setJoinRelayPin(byte joinRelayPin) {
|
void DCC::setJoinRelayPin(byte joinRelayPin) {
|
||||||
joinRelay=joinRelayPin;
|
joinRelay=joinRelayPin;
|
||||||
if (joinRelay!=UNUSED_PIN) {
|
if (joinRelay!=UNUSED_PIN) {
|
||||||
|
@ -68,6 +75,21 @@ 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) {
|
||||||
|
uint8_t brake;
|
||||||
|
if (tSpeed <= 1)
|
||||||
|
brake = 255;
|
||||||
|
else if (tSpeed >= 126)
|
||||||
|
brake = 0;
|
||||||
|
else
|
||||||
|
brake = 2 * (127-tSpeed);
|
||||||
|
DCCWaveform::mainTrack.motorDriver->setSignal(tDirection);
|
||||||
|
DCCWaveform::mainTrack.motorDriver->setBrake(brake);
|
||||||
|
}
|
||||||
|
#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
|
||||||
|
|
|
@ -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
|
||||||
|
|
|
@ -107,6 +107,7 @@ class DCCWaveform {
|
||||||
inline void setMaxAckPulseDuration(unsigned int i) {
|
inline void setMaxAckPulseDuration(unsigned int i) {
|
||||||
maxAckPulseDuration = i;
|
maxAckPulseDuration = i;
|
||||||
}
|
}
|
||||||
|
MotorDriver* motorDriver;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
@ -121,7 +122,7 @@ class DCCWaveform {
|
||||||
void checkAck();
|
void checkAck();
|
||||||
|
|
||||||
bool isMainTrack;
|
bool isMainTrack;
|
||||||
MotorDriver* motorDriver;
|
// MotorDriver* motorDriver;
|
||||||
// Transmission controller
|
// Transmission controller
|
||||||
byte transmitPacket[MAX_PACKET_SIZE+1]; // +1 for checksum
|
byte transmitPacket[MAX_PACKET_SIZE+1]; // +1 for checksum
|
||||||
byte transmitLength;
|
byte transmitLength;
|
||||||
|
|
|
@ -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;
|
||||||
|
|
||||||
|
@ -91,8 +92,8 @@ void MotorDriver::setPower(bool on) {
|
||||||
// on the Pololu board if brake is wired to ^D2.
|
// on the Pololu board if brake is wired to ^D2.
|
||||||
// Yes, this is an ugly special case
|
// Yes, this is an ugly special case
|
||||||
if (brakePin == 4 && invertBrake) {
|
if (brakePin == 4 && invertBrake) {
|
||||||
setBrake(true);
|
setBrake(255);
|
||||||
setBrake(false);
|
setBrake(0);
|
||||||
}
|
}
|
||||||
setHIGH(fastPowerPin);
|
setHIGH(fastPowerPin);
|
||||||
}
|
}
|
||||||
|
@ -107,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) {
|
||||||
|
|
|
@ -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;
|
||||||
|
|
Loading…
Reference in New Issue
Block a user