mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2025-07-30 19:03:44 +02:00
Compare commits
2 Commits
EX-RAIL-DC
...
archive/EX
Author | SHA1 | Date | |
---|---|---|---|
|
615fbeb291 | ||
|
15264e17ef |
14
DCC.cpp
14
DCC.cpp
@@ -61,15 +61,8 @@ void DCC::begin(const FSH * motorShieldName, MotorDriver * mainDriver, MotorDriv
|
||||
EEStore::init();
|
||||
|
||||
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) {
|
||||
joinRelay=joinRelayPin;
|
||||
if (joinRelay!=UNUSED_PIN) {
|
||||
@@ -79,13 +72,6 @@ void DCC::setJoinRelayPin(byte joinRelayPin) {
|
||||
}
|
||||
|
||||
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;
|
||||
setThrottle2(cab, speedCode);
|
||||
// retain speed for loco reminders
|
||||
|
@@ -65,9 +65,7 @@ void DCCWaveform::interruptHandler() {
|
||||
byte sigProg=progTrackSyncMain? sigMain : signalTransform[progTrack.state];
|
||||
|
||||
// Set the signal state for both tracks
|
||||
#ifndef DCdistrict
|
||||
mainTrack.motorDriver->setSignal(sigMain);
|
||||
#endif
|
||||
progTrack.motorDriver->setSignal(sigProg);
|
||||
|
||||
// Move on in the state engine
|
||||
|
@@ -107,27 +107,6 @@ class DCCWaveform {
|
||||
inline void setMaxAckPulseDuration(unsigned int 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:
|
||||
|
||||
|
@@ -1 +1 @@
|
||||
#define GITHUB_SHA "EX-RAIL-DC-20211109-2306"
|
||||
#define GITHUB_SHA "50fcbc0"
|
||||
|
21
IODevice.cpp
21
IODevice.cpp
@@ -160,7 +160,7 @@ void IODevice::write(VPIN vpin, int value) {
|
||||
return;
|
||||
}
|
||||
#ifdef DIAG_IO
|
||||
DIAG(F("IODevice::write(): Vpin ID %d not found!"), (int)vpin);
|
||||
//DIAG(F("IODevice::write(): Vpin ID %d not found!"), (int)vpin);
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -179,7 +179,7 @@ void IODevice::writeAnalogue(VPIN vpin, int value, uint8_t param1, uint16_t para
|
||||
return;
|
||||
}
|
||||
#ifdef DIAG_IO
|
||||
DIAG(F("IODevice::writeAnalogue(): Vpin ID %d not found!"), (int)vpin);
|
||||
//DIAG(F("IODevice::writeAnalogue(): Vpin ID %d not found!"), (int)vpin);
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -265,7 +265,7 @@ int IODevice::read(VPIN vpin) {
|
||||
return dev->_read(vpin);
|
||||
}
|
||||
#ifdef DIAG_IO
|
||||
DIAG(F("IODevice::read(): Vpin %d not found!"), (int)vpin);
|
||||
//DIAG(F("IODevice::read(): Vpin %d not found!"), (int)vpin);
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
@@ -288,17 +288,7 @@ int IODevice::readAnalogue(VPIN vpin) {
|
||||
// Minimal implementations of public HAL interface, to support Arduino pin I/O and nothing more.
|
||||
|
||||
void IODevice::begin() { DIAG(F("NO HAL CONFIGURED!")); }
|
||||
bool IODevice::configure(VPIN pin, ConfigTypeEnum, int, int p[]) {
|
||||
#ifdef DIAG_IO
|
||||
DIAG(F("Arduino _configurePullup Pin:%d Val:%d"), pin, p[0]);
|
||||
#endif
|
||||
if (p[0]) {
|
||||
pinMode(pin, INPUT_PULLUP);
|
||||
} else {
|
||||
pinMode(pin, INPUT);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
bool IODevice::configure(VPIN, ConfigTypeEnum, int, int []) { return true; }
|
||||
void IODevice::write(VPIN vpin, int value) {
|
||||
digitalWrite(vpin, value);
|
||||
pinMode(vpin, OUTPUT);
|
||||
@@ -307,6 +297,7 @@ void IODevice::writeAnalogue(VPIN, int, uint8_t, uint16_t) {}
|
||||
bool IODevice::isBusy(VPIN) { return false; }
|
||||
bool IODevice::hasCallback(VPIN) { return false; }
|
||||
int IODevice::read(VPIN vpin) {
|
||||
pinMode(vpin, INPUT_PULLUP);
|
||||
return !digitalRead(vpin); // Return inverted state (5v=0, 0v=1)
|
||||
}
|
||||
int IODevice::readAnalogue(VPIN vpin) {
|
||||
@@ -443,7 +434,7 @@ int ArduinoPins::_readAnalogue(VPIN vpin) {
|
||||
interrupts();
|
||||
|
||||
#ifdef DIAG_IO
|
||||
DIAG(F("Arduino Read Pin:%d Value:%d"), pin, value);
|
||||
//DIAG(F("Arduino Read Pin:%d Value:%d"), pin, value);
|
||||
#endif
|
||||
return value;
|
||||
}
|
||||
|
@@ -31,7 +31,6 @@ bool MotorDriver::commonFaultPin=false;
|
||||
|
||||
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) {
|
||||
brakePWM=false;
|
||||
powerPin=power_pin;
|
||||
getFastPin(F("POWER"),powerPin,fastPowerPin);
|
||||
pinMode(powerPin, OUTPUT);
|
||||
@@ -54,7 +53,7 @@ MotorDriver::MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, int8
|
||||
brakePin=invertBrake ? 0-brake_pin : brake_pin;
|
||||
getFastPin(F("BRAKE"),brakePin,fastBrakePin);
|
||||
pinMode(brakePin, OUTPUT);
|
||||
// setBrake(0); moved out to DCC::begin
|
||||
setBrake(false);
|
||||
}
|
||||
else brakePin=UNUSED_PIN;
|
||||
|
||||
@@ -90,11 +89,8 @@ void MotorDriver::setPower(bool on) {
|
||||
if (on) {
|
||||
// toggle brake before turning power on - resets overcurrent error
|
||||
// on the Pololu board if brake is wired to ^D2.
|
||||
// Yes, this is an ugly special case
|
||||
if (brakePin == 4 && invertBrake) {
|
||||
setBrake(255);
|
||||
setBrake(0);
|
||||
}
|
||||
setBrake(true);
|
||||
setBrake(false);
|
||||
setHIGH(fastPowerPin);
|
||||
}
|
||||
else setLOW(fastPowerPin);
|
||||
@@ -108,29 +104,10 @@ void MotorDriver::setPower(bool on) {
|
||||
// (HIGH == release brake) and setBrake does
|
||||
// compensate for that.
|
||||
//
|
||||
void MotorDriver::setBrake(uint8_t intensity) {
|
||||
void MotorDriver::setBrake(bool on) {
|
||||
if (brakePin == UNUSED_PIN) return;
|
||||
DIAG(F("Brake pin=%d val=%d"),brakePin,intensity);
|
||||
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);
|
||||
if (on ^ invertBrake) setHIGH(fastBrakePin);
|
||||
else setLOW(fastBrakePin);
|
||||
}
|
||||
|
||||
void MotorDriver::setSignal( bool high) {
|
||||
|
@@ -46,7 +46,7 @@ class MotorDriver {
|
||||
byte current_pin, float senseFactor, unsigned int tripMilliamps, byte faultPin);
|
||||
virtual void setPower( bool on);
|
||||
virtual void setSignal( bool high);
|
||||
virtual void setBrake(uint8_t);
|
||||
virtual void setBrake( bool on);
|
||||
virtual int getCurrentRaw();
|
||||
virtual unsigned int raw2mA( int raw);
|
||||
virtual int mA2raw( unsigned int mA);
|
||||
@@ -69,7 +69,6 @@ class MotorDriver {
|
||||
FASTPIN fastPowerPin,fastSignalPin, fastSignalPin2, fastBrakePin,fastFaultPin;
|
||||
bool dualSignal; // true to use signalPin2
|
||||
bool invertBrake; // brake pin passed as negative means pin is inverted
|
||||
bool brakePWM; // brake is used for PWM
|
||||
float senseFactor;
|
||||
int senseOffset;
|
||||
unsigned int tripMilliamps;
|
||||
|
@@ -48,11 +48,6 @@
|
||||
new MotorDriver(3, 12, UNUSED_PIN, UNUSED_PIN, A0, 2.99, 2000, UNUSED_PIN), \
|
||||
new MotorDriver(11, 13, UNUSED_PIN, UNUSED_PIN, A1, 2.99, 2000, UNUSED_PIN)
|
||||
|
||||
// TO GET THE DC district feature use this shield definition
|
||||
#define STD_DCC_DC_SHIELD F("STD_DCC_DC_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)
|
||||
|
||||
// Pololu Motor Shield
|
||||
#define POLOLU_MOTOR_SHIELD F("POLOLU_MOTOR_SHIELD"), \
|
||||
new MotorDriver( 9, 7, UNUSED_PIN, -4, A0, 18, 3000, 12), \
|
||||
@@ -87,9 +82,5 @@
|
||||
#define IBT_2_WITH_ARDUINO F("IBT_2_WITH_ARDUINO_SHIELD"), \
|
||||
new MotorDriver(4, 5, 6, UNUSED_PIN, A5, 41.54, 5000, UNUSED_PIN), \
|
||||
new MotorDriver(11, 13, UNUSED_PIN, UNUSED_PIN, A1, 2.99, 2000, UNUSED_PIN)
|
||||
// YFROBOT Motor Shield (V3.1)
|
||||
#define YFROBOT_MOTOR_SHIELD F("YFROBOT_MOTOR_SHIELD"), \
|
||||
new MotorDriver(5, 4, UNUSED_PIN, UNUSED_PIN, A0, 2.99, 2000, UNUSED_PIN), \
|
||||
new MotorDriver(6, 7, UNUSED_PIN, UNUSED_PIN, A1, 2.99, 2000, UNUSED_PIN)
|
||||
|
||||
#endif
|
||||
|
10
RMFT2.cpp
10
RMFT2.cpp
@@ -66,16 +66,6 @@ byte RMFT2::flags[MAX_FLAGS];
|
||||
byte opcode=GET_OPCODE;
|
||||
if (opcode==OPCODE_ENDEXRAIL) break;
|
||||
|
||||
switch (opcode) {
|
||||
case OPCODE_AT:
|
||||
case OPCODE_AFTER:
|
||||
case OPCODE_IF:
|
||||
case OPCODE_IFNOT:
|
||||
int16_t pin = (int16_t)GET_OPERAND(0);
|
||||
if (pin<0) pin = -pin;
|
||||
IODevice::configureInput((VPIN)pin,true);
|
||||
}
|
||||
|
||||
if (opcode==OPCODE_SIGNAL) {
|
||||
VPIN red=GET_OPERAND(0);
|
||||
VPIN amber=GET_OPERAND(1);
|
||||
|
BIN
Release - Architecture Doc/CS-EX-Arch-v1-0_sized.png
Normal file
BIN
Release - Architecture Doc/CS-EX-Arch-v1-0_sized.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 108 KiB |
BIN
Release - Architecture Doc/CommandStation-EX-Arch-v1-0.png
Normal file
BIN
Release - Architecture Doc/CommandStation-EX-Arch-v1-0.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 107 KiB |
@@ -23,10 +23,6 @@ The configuration file for DCC-EX Command Station
|
||||
|
||||
**********************************************************************/
|
||||
|
||||
// SPECIAL CONFIG WITH MAIN AS DC (PWM) track reacting on cab #2.
|
||||
//
|
||||
#define DCdistrict 2
|
||||
|
||||
/////////////////////////////////////////////////////////////////////////////////////
|
||||
// NOTE: Before connecting these boards and selecting one in this software
|
||||
// check the quick install guides!!! Some of these boards require a voltage
|
||||
@@ -42,11 +38,10 @@ The configuration file for DCC-EX Command Station
|
||||
// FIREBOX_MK1 : The Firebox MK1
|
||||
// FIREBOX_MK1S : The Firebox MK1S
|
||||
// IBT_2_WITH_ARDUINO : Arduino Motor Shield for PROG and IBT-2 for MAIN
|
||||
// STD_DCC_DC_SHIELD : as STANDARD but with brake so MAIN can be run as DC (PWM)
|
||||
// |
|
||||
// +-----------------------v
|
||||
//
|
||||
#define MOTOR_SHIELD_TYPE STD_DCC_DC_SHIELD
|
||||
#define MOTOR_SHIELD_TYPE STANDARD_MOTOR_SHIELD
|
||||
/////////////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// The IP port to talk to a WIFI or Ethernet shield.
|
||||
|
BIN
ex-rail.zip
Normal file
BIN
ex-rail.zip
Normal file
Binary file not shown.
@@ -3,7 +3,7 @@
|
||||
|
||||
#include "StringFormatter.h"
|
||||
|
||||
#define VERSION "3.2.0 DCrc2"
|
||||
#define VERSION "3.2.0"
|
||||
// 3.2.0 Major functional and non-functional changes.
|
||||
// New HAL added for I/O (digital and analogue inputs and outputs, servos etc).
|
||||
// Support for MCP23008, MCP23017 and PCF9584 I2C GPIO Extender modules.
|
||||
|
Reference in New Issue
Block a user