mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-11-30 03:26:13 +01:00
RailCom cutout for MAIN and PROG track
This commit is contained in:
parent
818e05b425
commit
65b9079337
|
@ -1,4 +1,5 @@
|
||||||
/*
|
/*
|
||||||
|
* @ 2024 Arkadiusz Hahn
|
||||||
* © 2021 Neil McKechnie
|
* © 2021 Neil McKechnie
|
||||||
* © 2021 Mike S
|
* © 2021 Mike S
|
||||||
* © 2021 Fred Decker
|
* © 2021 Fred Decker
|
||||||
|
@ -35,6 +36,8 @@
|
||||||
DCCWaveform DCCWaveform::mainTrack(PREAMBLE_BITS_MAIN, true);
|
DCCWaveform DCCWaveform::mainTrack(PREAMBLE_BITS_MAIN, true);
|
||||||
DCCWaveform DCCWaveform::progTrack(PREAMBLE_BITS_PROG, false);
|
DCCWaveform DCCWaveform::progTrack(PREAMBLE_BITS_PROG, false);
|
||||||
|
|
||||||
|
bool DCCWaveform::supportsRailcom=false;
|
||||||
|
bool DCCWaveform::useRailcom=false;
|
||||||
|
|
||||||
// This bitmask has 9 entries as each byte is trasmitted as a zero + 8 bits.
|
// This bitmask has 9 entries as each byte is trasmitted as a zero + 8 bits.
|
||||||
const byte bitMask[] = {0x00, 0x80, 0x40, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01};
|
const byte bitMask[] = {0x00, 0x80, 0x40, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01};
|
||||||
|
@ -62,6 +65,20 @@ const bool signalTransform[]={
|
||||||
/* WAVE_PENDING (should not happen) -> */ LOW};
|
/* WAVE_PENDING (should not happen) -> */ LOW};
|
||||||
|
|
||||||
void DCCWaveform::begin() {
|
void DCCWaveform::begin() {
|
||||||
|
// supportsRailcom depends on hardware capability
|
||||||
|
supportsRailcom = TrackManager::isRailcomCapable();
|
||||||
|
// useRailcom is user switchable at run time.
|
||||||
|
useRailcom=supportsRailcom;
|
||||||
|
|
||||||
|
if (useRailcom) {
|
||||||
|
DIAG(F("Railcom is enabled"));
|
||||||
|
} else {
|
||||||
|
DIAG(F("Railcom is disabled"));
|
||||||
|
}
|
||||||
|
|
||||||
|
TrackManager::setCutout(false,false);
|
||||||
|
TrackManager::setPROGCutout(false,false);
|
||||||
|
|
||||||
DCCTimer::begin(DCCWaveform::interruptHandler);
|
DCCTimer::begin(DCCWaveform::interruptHandler);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -69,9 +86,24 @@ void DCCWaveform::loop() {
|
||||||
// empty placemarker in case ESP32 needs something here
|
// empty placemarker in case ESP32 needs something here
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
bool DCCWaveform::setUseRailcom(bool on) {
|
||||||
|
if (!supportsRailcom) return false;
|
||||||
|
useRailcom=on;
|
||||||
|
if (!on) {
|
||||||
|
// turn off any existing cutout
|
||||||
|
TrackManager::setCutout(false);
|
||||||
|
TrackManager::setPROGCutout(false);
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
#pragma GCC push_options
|
#pragma GCC push_options
|
||||||
#pragma GCC optimize ("-O3")
|
#pragma GCC optimize ("-O3")
|
||||||
void DCCWaveform::interruptHandler() {
|
void DCCWaveform::interruptHandler() {
|
||||||
|
|
||||||
|
|
||||||
// call the timer edge sensitive actions for progtrack and maintrack
|
// call the timer edge sensitive actions for progtrack and maintrack
|
||||||
// member functions would be cleaner but have more overhead
|
// member functions would be cleaner but have more overhead
|
||||||
byte sigMain= signalTransform[mainTrack.state];
|
byte sigMain= signalTransform[mainTrack.state];
|
||||||
|
@ -84,15 +116,24 @@ void DCCWaveform::interruptHandler() {
|
||||||
// Refresh the values in the ADCee object buffering the values of the ADC HW
|
// Refresh the values in the ADCee object buffering the values of the ADC HW
|
||||||
ADCee::scan();
|
ADCee::scan();
|
||||||
|
|
||||||
|
// WAVE_START is at start of bit where we need to find
|
||||||
|
// out if this is an railcom start or stop time
|
||||||
|
if (useRailcom) {
|
||||||
|
if ((mainTrack.state==WAVE_START) || (mainTrack.state== WAVE_MID_1)) mainTrack.railcom2();
|
||||||
|
if ((progTrack.state==WAVE_START) || (progTrack.state== WAVE_MID_1)) progTrack.railcom2();
|
||||||
|
}
|
||||||
|
|
||||||
// Move on in the state engine
|
// Move on in the state engine
|
||||||
mainTrack.state=stateTransform[mainTrack.state];
|
mainTrack.state=stateTransform[mainTrack.state];
|
||||||
progTrack.state=stateTransform[progTrack.state];
|
progTrack.state=stateTransform[progTrack.state];
|
||||||
|
|
||||||
// WAVE_PENDING means we dont yet know what the next bit is
|
// WAVE_PENDING means we dont yet know what the next bit is
|
||||||
if (mainTrack.state==WAVE_PENDING) mainTrack.interrupt2();
|
if ((mainTrack.state==WAVE_PENDING) || (mainTrack.state== WAVE_START)) mainTrack.interrupt2();
|
||||||
if (progTrack.state==WAVE_PENDING) progTrack.interrupt2();
|
if ((progTrack.state==WAVE_PENDING) || (progTrack.state == WAVE_START)) {
|
||||||
else DCCACK::checkAck(progTrack.getResets());
|
progTrack.interrupt2();
|
||||||
|
} else {
|
||||||
|
DCCACK::checkAck(progTrack.getResets());
|
||||||
|
}
|
||||||
}
|
}
|
||||||
#pragma GCC pop_options
|
#pragma GCC pop_options
|
||||||
|
|
||||||
|
@ -111,10 +152,38 @@ DCCWaveform::DCCWaveform( byte preambleBits, bool isMain) {
|
||||||
// The +1 below is to allow the preamble generator to create the stop bit
|
// The +1 below is to allow the preamble generator to create the stop bit
|
||||||
// for the previous packet.
|
// for the previous packet.
|
||||||
requiredPreambles = preambleBits+1;
|
requiredPreambles = preambleBits+1;
|
||||||
|
requiredPreambles <<=1; // double the number of preamble wave halves
|
||||||
|
|
||||||
|
remainingPreambles=0;
|
||||||
bytes_sent = 0;
|
bytes_sent = 0;
|
||||||
bits_sent = 0;
|
bits_sent = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#pragma GCC push_options
|
||||||
|
#pragma GCC optimize ("-O3")
|
||||||
|
void DCCWaveform::railcom2() {
|
||||||
|
bool cutout;
|
||||||
|
if (remainingPreambles==(requiredPreambles-4)) {
|
||||||
|
cutout=true;
|
||||||
|
} else if (remainingPreambles==(requiredPreambles-11)) {
|
||||||
|
cutout=false;
|
||||||
|
} else {
|
||||||
|
return; // neither start or end of cutout, do nothing
|
||||||
|
}
|
||||||
|
|
||||||
|
if (isMainTrack) {
|
||||||
|
if (TrackManager::progTrackSyncMain) {// we are main track and synced so we take care of prog track as well
|
||||||
|
TrackManager::setPROGCutout(cutout,true);
|
||||||
|
}
|
||||||
|
TrackManager::setCutout(cutout,true);
|
||||||
|
} else {
|
||||||
|
if (!TrackManager::progTrackSyncMain) {// we are prog track and not synced so we take care of ourselves
|
||||||
|
TrackManager::setPROGCutout(cutout,true);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#pragma GCC pop_options
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#pragma GCC push_options
|
#pragma GCC push_options
|
||||||
|
@ -125,14 +194,18 @@ void DCCWaveform::interrupt2() {
|
||||||
// or WAVE_HIGH_0 for a 0 bit.
|
// or WAVE_HIGH_0 for a 0 bit.
|
||||||
|
|
||||||
if (remainingPreambles > 0 ) {
|
if (remainingPreambles > 0 ) {
|
||||||
|
if (state==WAVE_PENDING) {
|
||||||
state=WAVE_MID_1; // switch state to trigger LOW on next interrupt
|
state=WAVE_MID_1; // switch state to trigger LOW on next interrupt
|
||||||
|
}
|
||||||
remainingPreambles--;
|
remainingPreambles--;
|
||||||
|
|
||||||
// Update free memory diagnostic as we don't have anything else to do this time.
|
// Update free memory diagnostic as we don't have anything else to do this time.
|
||||||
// Allow for checkAck and its called functions using 22 bytes more.
|
// Allow for checkAck and its called functions using 22 bytes more.
|
||||||
DCCTimer::updateMinimumFreeMemoryISR(22);
|
DCCTimer::updateMinimumFreeMemoryISR(22);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (state==WAVE_PENDING) {
|
||||||
// Wave has gone HIGH but what happens next depends on the bit to be transmitted
|
// Wave has gone HIGH but what happens next depends on the bit to be transmitted
|
||||||
// beware OF 9-BIT MASK generating a zero to start each byte
|
// beware OF 9-BIT MASK generating a zero to start each byte
|
||||||
state=(transmitPacket[bytes_sent] & bitMask[bits_sent])? WAVE_MID_1 : WAVE_HIGH_0;
|
state=(transmitPacket[bytes_sent] & bitMask[bits_sent])? WAVE_MID_1 : WAVE_HIGH_0;
|
||||||
|
@ -174,6 +247,7 @@ void DCCWaveform::interrupt2() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
#pragma GCC pop_options
|
#pragma GCC pop_options
|
||||||
|
|
||||||
// Wait until there is no packet pending, then make this pending
|
// Wait until there is no packet pending, then make this pending
|
||||||
|
|
|
@ -52,6 +52,11 @@ class DCCWaveform {
|
||||||
static void loop();
|
static void loop();
|
||||||
static DCCWaveform mainTrack;
|
static DCCWaveform mainTrack;
|
||||||
static DCCWaveform progTrack;
|
static DCCWaveform progTrack;
|
||||||
|
|
||||||
|
static bool supportsRailcom;
|
||||||
|
static bool useRailcom;
|
||||||
|
static bool setUseRailcom(bool on);
|
||||||
|
|
||||||
inline void clearRepeats() { transmitRepeats=0; }
|
inline void clearRepeats() { transmitRepeats=0; }
|
||||||
#ifndef ARDUINO_ARCH_ESP32
|
#ifndef ARDUINO_ARCH_ESP32
|
||||||
inline void clearResets() { sentResetsSincePacket=0; }
|
inline void clearResets() { sentResetsSincePacket=0; }
|
||||||
|
@ -87,6 +92,7 @@ class DCCWaveform {
|
||||||
#endif
|
#endif
|
||||||
static void interruptHandler();
|
static void interruptHandler();
|
||||||
void interrupt2();
|
void interrupt2();
|
||||||
|
void railcom2();
|
||||||
|
|
||||||
bool isMainTrack;
|
bool isMainTrack;
|
||||||
// Transmission controller
|
// Transmission controller
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
/*
|
/* @ 2024 Arkadiusz Hahn
|
||||||
* © 2022-2023 Paul M Antoine
|
* © 2022-2023 Paul M Antoine
|
||||||
* © 2021 Mike S
|
* © 2021 Mike S
|
||||||
* © 2021 Fred Decker
|
* © 2021 Fred Decker
|
||||||
|
@ -32,6 +32,7 @@ unsigned long MotorDriver::globalOverloadStart = 0;
|
||||||
volatile portreg_t shadowPORTA;
|
volatile portreg_t shadowPORTA;
|
||||||
volatile portreg_t shadowPORTB;
|
volatile portreg_t shadowPORTB;
|
||||||
volatile portreg_t shadowPORTC;
|
volatile portreg_t shadowPORTC;
|
||||||
|
volatile portreg_t shadowPORTH;
|
||||||
|
|
||||||
MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin,
|
MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin,
|
||||||
byte current_pin, float sense_factor, unsigned int trip_milliamps, int16_t fault_pin) {
|
byte current_pin, float sense_factor, unsigned int trip_milliamps, int16_t fault_pin) {
|
||||||
|
@ -52,17 +53,17 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
|
||||||
|
|
||||||
fastSignalPin.shadowinout = NULL;
|
fastSignalPin.shadowinout = NULL;
|
||||||
if (HAVE_PORTA(fastSignalPin.inout == &PORTA)) {
|
if (HAVE_PORTA(fastSignalPin.inout == &PORTA)) {
|
||||||
DIAG(F("Found PORTA pin %d"),signalPin);
|
DIAG(F("Found SignalPin PORTA pin %d"),signalPin);
|
||||||
fastSignalPin.shadowinout = fastSignalPin.inout;
|
fastSignalPin.shadowinout = fastSignalPin.inout;
|
||||||
fastSignalPin.inout = &shadowPORTA;
|
fastSignalPin.inout = &shadowPORTA;
|
||||||
}
|
}
|
||||||
if (HAVE_PORTB(fastSignalPin.inout == &PORTB)) {
|
if (HAVE_PORTB(fastSignalPin.inout == &PORTB)) {
|
||||||
DIAG(F("Found PORTB pin %d"),signalPin);
|
DIAG(F("Found SignalPin PORTB pin %d"),signalPin);
|
||||||
fastSignalPin.shadowinout = fastSignalPin.inout;
|
fastSignalPin.shadowinout = fastSignalPin.inout;
|
||||||
fastSignalPin.inout = &shadowPORTB;
|
fastSignalPin.inout = &shadowPORTB;
|
||||||
}
|
}
|
||||||
if (HAVE_PORTC(fastSignalPin.inout == &PORTC)) {
|
if (HAVE_PORTC(fastSignalPin.inout == &PORTC)) {
|
||||||
DIAG(F("Found PORTC pin %d"),signalPin);
|
DIAG(F("Found SignalPin PORTC pin %d"),signalPin);
|
||||||
fastSignalPin.shadowinout = fastSignalPin.inout;
|
fastSignalPin.shadowinout = fastSignalPin.inout;
|
||||||
fastSignalPin.inout = &shadowPORTC;
|
fastSignalPin.inout = &shadowPORTC;
|
||||||
}
|
}
|
||||||
|
@ -75,17 +76,17 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
|
||||||
|
|
||||||
fastSignalPin2.shadowinout = NULL;
|
fastSignalPin2.shadowinout = NULL;
|
||||||
if (HAVE_PORTA(fastSignalPin2.inout == &PORTA)) {
|
if (HAVE_PORTA(fastSignalPin2.inout == &PORTA)) {
|
||||||
DIAG(F("Found PORTA pin %d"),signalPin2);
|
DIAG(F("Found SignalPin2 PORTA pin %d"),signalPin2);
|
||||||
fastSignalPin2.shadowinout = fastSignalPin2.inout;
|
fastSignalPin2.shadowinout = fastSignalPin2.inout;
|
||||||
fastSignalPin2.inout = &shadowPORTA;
|
fastSignalPin2.inout = &shadowPORTA;
|
||||||
}
|
}
|
||||||
if (HAVE_PORTB(fastSignalPin2.inout == &PORTB)) {
|
if (HAVE_PORTB(fastSignalPin2.inout == &PORTB)) {
|
||||||
DIAG(F("Found PORTB pin %d"),signalPin2);
|
DIAG(F("Found SignalPin2 PORTB pin %d"),signalPin2);
|
||||||
fastSignalPin2.shadowinout = fastSignalPin2.inout;
|
fastSignalPin2.shadowinout = fastSignalPin2.inout;
|
||||||
fastSignalPin2.inout = &shadowPORTB;
|
fastSignalPin2.inout = &shadowPORTB;
|
||||||
}
|
}
|
||||||
if (HAVE_PORTC(fastSignalPin2.inout == &PORTC)) {
|
if (HAVE_PORTC(fastSignalPin2.inout == &PORTC)) {
|
||||||
DIAG(F("Found PORTC pin %d"),signalPin2);
|
DIAG(F("Found SignalPin2 PORTC pin %d"),signalPin2);
|
||||||
fastSignalPin2.shadowinout = fastSignalPin2.inout;
|
fastSignalPin2.shadowinout = fastSignalPin2.inout;
|
||||||
fastSignalPin2.inout = &shadowPORTC;
|
fastSignalPin2.inout = &shadowPORTC;
|
||||||
}
|
}
|
||||||
|
@ -102,6 +103,31 @@ 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);
|
||||||
|
fastBrakePin.shadowinout = NULL;
|
||||||
|
|
||||||
|
//DIAG(F("Found BrakePin %d "), brake_pin);
|
||||||
|
if (HAVE_PORTA(fastBrakePin.inout == &PORTA)) {
|
||||||
|
DIAG(F("Found BrakePin PORTA pin %d"),brakePin);
|
||||||
|
fastBrakePin.shadowinout = fastBrakePin.inout;
|
||||||
|
fastBrakePin.inout = &shadowPORTA;
|
||||||
|
}
|
||||||
|
if (HAVE_PORTB(fastBrakePin.inout == &PORTB)) {
|
||||||
|
DIAG(F("Found BrakePin PORTB pin %d"),brakePin);
|
||||||
|
fastBrakePin.shadowinout = fastBrakePin.inout;
|
||||||
|
fastBrakePin.inout = &shadowPORTB;
|
||||||
|
}
|
||||||
|
if (HAVE_PORTC(fastBrakePin.inout == &PORTC)) {
|
||||||
|
DIAG(F("Found BrakePin PORTC pin %d"),brakePin);
|
||||||
|
fastBrakePin.shadowinout = fastBrakePin.inout;
|
||||||
|
fastBrakePin.inout = &shadowPORTC;
|
||||||
|
}
|
||||||
|
if (HAVE_PORTH(fastBrakePin.inout == &PORTH)) {
|
||||||
|
DIAG(F("Found BrakePin PORTH pin %d"),brakePin);
|
||||||
|
fastBrakePin.shadowinout = fastBrakePin.inout;
|
||||||
|
fastBrakePin.inout = &shadowPORTH;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
setBrake(true); // start with brake on in case we hace DC stuff going on
|
setBrake(true); // start with brake on in case we hace DC stuff going on
|
||||||
} else {
|
} else {
|
||||||
brakePin=UNUSED_PIN;
|
brakePin=UNUSED_PIN;
|
||||||
|
@ -170,6 +196,9 @@ bool MotorDriver::isPWMCapable() {
|
||||||
return (!dualSignal) && DCCTimer::isPWMPin(signalPin);
|
return (!dualSignal) && DCCTimer::isPWMPin(signalPin);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool MotorDriver::isRailcomCapable() {
|
||||||
|
return (!dualSignal) && (brakePin!=UNUSED_PIN);
|
||||||
|
}
|
||||||
|
|
||||||
void MotorDriver::setPower(POWERMODE mode) {
|
void MotorDriver::setPower(POWERMODE mode) {
|
||||||
if (powerMode == mode) return;
|
if (powerMode == mode) return;
|
||||||
|
@ -195,23 +224,6 @@ void MotorDriver::setPower(POWERMODE mode) {
|
||||||
powerMode=mode;
|
powerMode=mode;
|
||||||
}
|
}
|
||||||
|
|
||||||
// setBrake applies brake if on == true. So to get
|
|
||||||
// voltage from the motor bride one needs to do a
|
|
||||||
// setBrake(false).
|
|
||||||
// If the brakePin is negative that means the sense
|
|
||||||
// of the brake pin on the motor bridge is inverted
|
|
||||||
// (HIGH == release brake) and setBrake does
|
|
||||||
// compensate for that.
|
|
||||||
//
|
|
||||||
void MotorDriver::setBrake(bool on, bool interruptContext) {
|
|
||||||
if (brakePin == UNUSED_PIN) return;
|
|
||||||
if (!interruptContext) {noInterrupts();}
|
|
||||||
if (on ^ invertBrake)
|
|
||||||
setHIGH(fastBrakePin);
|
|
||||||
else
|
|
||||||
setLOW(fastBrakePin);
|
|
||||||
if (!interruptContext) {interrupts();}
|
|
||||||
}
|
|
||||||
|
|
||||||
bool MotorDriver::canMeasureCurrent() {
|
bool MotorDriver::canMeasureCurrent() {
|
||||||
return currentPin!=UNUSED_PIN;
|
return currentPin!=UNUSED_PIN;
|
||||||
|
@ -455,7 +467,7 @@ void MotorDriver::getFastPin(const FSH* type,int pin, bool input, FASTPIN & res
|
||||||
result.inout = portOutputRegister(port);
|
result.inout = portOutputRegister(port);
|
||||||
result.maskHIGH = digitalPinToBitMask(pin);
|
result.maskHIGH = digitalPinToBitMask(pin);
|
||||||
result.maskLOW = ~result.maskHIGH;
|
result.maskLOW = ~result.maskHIGH;
|
||||||
// DIAG(F(" port=0x%x, inoutpin=0x%x, isinput=%d, mask=0x%x"),port, result.inout,input,result.maskHIGH);
|
//DIAG(F("MotorDriver::getFastPin port=0x%x, inoutpin=0x%x, isinput=%d, mask=0x%x"),port, result.inout,input,result.maskHIGH);
|
||||||
}
|
}
|
||||||
|
|
||||||
///////////////////////////////////////////////////////////////////////////////////////////
|
///////////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
|
@ -43,6 +43,7 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO
|
||||||
#define HAVE_PORTA(X) X
|
#define HAVE_PORTA(X) X
|
||||||
#define HAVE_PORTB(X) X
|
#define HAVE_PORTB(X) X
|
||||||
#define HAVE_PORTC(X) X
|
#define HAVE_PORTC(X) X
|
||||||
|
#define HAVE_PORTH(X) X
|
||||||
#endif
|
#endif
|
||||||
#if defined(ARDUINO_AVR_UNO)
|
#if defined(ARDUINO_AVR_UNO)
|
||||||
#define HAVE_PORTB(X) X
|
#define HAVE_PORTB(X) X
|
||||||
|
@ -74,7 +75,9 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO
|
||||||
#ifndef HAVE_PORTC
|
#ifndef HAVE_PORTC
|
||||||
#define HAVE_PORTC(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
|
#define HAVE_PORTC(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
|
||||||
#endif
|
#endif
|
||||||
|
#ifndef HAVE_PORTH
|
||||||
|
#define HAVE_PORTH(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
|
||||||
|
#endif
|
||||||
// Virtualised Motor shield 1-track hardware Interface
|
// Virtualised Motor shield 1-track hardware Interface
|
||||||
|
|
||||||
#ifndef UNUSED_PIN // sync define with the one in MotorDrivers.h
|
#ifndef UNUSED_PIN // sync define with the one in MotorDrivers.h
|
||||||
|
@ -110,6 +113,7 @@ struct FASTPIN {
|
||||||
extern volatile portreg_t shadowPORTA;
|
extern volatile portreg_t shadowPORTA;
|
||||||
extern volatile portreg_t shadowPORTB;
|
extern volatile portreg_t shadowPORTB;
|
||||||
extern volatile portreg_t shadowPORTC;
|
extern volatile portreg_t shadowPORTC;
|
||||||
|
extern volatile portreg_t shadowPORTH;
|
||||||
|
|
||||||
enum class POWERMODE : byte { OFF, ON, OVERLOAD, ALERT };
|
enum class POWERMODE : byte { OFF, ON, OVERLOAD, ALERT };
|
||||||
|
|
||||||
|
@ -118,35 +122,59 @@ class MotorDriver {
|
||||||
|
|
||||||
MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin,
|
MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin,
|
||||||
byte current_pin, float senseFactor, unsigned int tripMilliamps, int16_t fault_pin);
|
byte current_pin, float senseFactor, unsigned int tripMilliamps, int16_t fault_pin);
|
||||||
|
|
||||||
void setPower( POWERMODE mode);
|
void setPower( POWERMODE mode);
|
||||||
|
|
||||||
POWERMODE getPower() { return powerMode;}
|
POWERMODE getPower() { return powerMode;}
|
||||||
|
|
||||||
// as the port registers can be shadowed to get syncronized DCC signals
|
// as the port registers can be shadowed to get syncronized DCC signals
|
||||||
// we need to take care of that and we have to turn off interrupts if
|
// we need to take care of that and we have to turn off interrupts if
|
||||||
// we setSignal() or setBrake() or setPower() during that time as
|
// we setSignal() or setBrake() or setPower() during that time as
|
||||||
// otherwise the call from interrupt context can undo whatever we do
|
// otherwise the call from interrupt context can undo whatever we do
|
||||||
// from outside interrupt
|
// from outside interrupt
|
||||||
void setBrake( bool on, bool interruptContext=false);
|
|
||||||
|
|
||||||
|
// setBrake applies brake if on == true. So to get
|
||||||
|
// voltage from the motor bride one needs to do a
|
||||||
|
// setBrake(false).
|
||||||
|
// If the brakePin is negative that means the sense
|
||||||
|
// of the brake pin on the motor bridge is inverted
|
||||||
|
// (HIGH == release brake) and setBrake does
|
||||||
|
// compensate for that.
|
||||||
|
__attribute__((always_inline)) inline void setBrake(bool on, bool interruptContext=false) {
|
||||||
|
if (brakePin == UNUSED_PIN) return;
|
||||||
|
if (!interruptContext) {noInterrupts();}
|
||||||
|
if (on ^ invertBrake) {
|
||||||
|
setHIGH(fastBrakePin);
|
||||||
|
} else {
|
||||||
|
setLOW(fastBrakePin);
|
||||||
|
}
|
||||||
|
if (!interruptContext) {interrupts();}
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
__attribute__((always_inline)) inline void setSignal( bool high) {
|
__attribute__((always_inline)) inline void setSignal( bool high) {
|
||||||
if (trackPWM) {
|
if (trackPWM) {
|
||||||
DCCTimer::setPWM(signalPin,high);
|
DCCTimer::setPWM(signalPin,high);
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
if (high) {
|
if (high) {
|
||||||
setHIGH(fastSignalPin);
|
setHIGH(fastSignalPin);
|
||||||
if (dualSignal) setLOW(fastSignalPin2);
|
if (dualSignal) setLOW(fastSignalPin2);
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
setLOW(fastSignalPin);
|
setLOW(fastSignalPin);
|
||||||
if (dualSignal) setHIGH(fastSignalPin2);
|
if (dualSignal) setHIGH(fastSignalPin2);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
inline void enableSignal(bool on) {
|
inline void enableSignal(bool on) {
|
||||||
if (on)
|
if (on) {
|
||||||
pinMode(signalPin, OUTPUT);
|
pinMode(signalPin, OUTPUT);
|
||||||
else
|
} else {
|
||||||
pinMode(signalPin, INPUT);
|
pinMode(signalPin, INPUT);
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
inline pinpair getSignalPin() { return pinpair(signalPin,signalPin2); };
|
inline pinpair getSignalPin() { return pinpair(signalPin,signalPin2); };
|
||||||
void setDCSignal(byte speedByte);
|
void setDCSignal(byte speedByte);
|
||||||
void throttleInrush(bool on);
|
void throttleInrush(bool on);
|
||||||
|
@ -178,6 +206,7 @@ class MotorDriver {
|
||||||
return rawCurrentTripValue;
|
return rawCurrentTripValue;
|
||||||
}
|
}
|
||||||
bool isPWMCapable();
|
bool isPWMCapable();
|
||||||
|
bool isRailcomCapable();
|
||||||
bool canMeasureCurrent();
|
bool canMeasureCurrent();
|
||||||
bool trackPWM = false; // this track uses PWM timer to generate the DCC waveform
|
bool trackPWM = false; // this track uses PWM timer to generate the DCC waveform
|
||||||
bool commonFaultPin = false; // This is a stupid motor shield which has only a common fault pin for both outputs
|
bool commonFaultPin = false; // This is a stupid motor shield which has only a common fault pin for both outputs
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
/*
|
/* @ 2024 Arkadiusz Hahn
|
||||||
* © 2022 Chris Harlow
|
* © 2022 Chris Harlow
|
||||||
* © 2022 Harald Barth
|
* © 2022 Harald Barth
|
||||||
* All rights reserved.
|
* All rights reserved.
|
||||||
|
@ -159,10 +159,41 @@ void TrackManager::setDCCSignal( bool on) {
|
||||||
HAVE_PORTC(PORTC=shadowPORTC);
|
HAVE_PORTC(PORTC=shadowPORTC);
|
||||||
}
|
}
|
||||||
|
|
||||||
void TrackManager::setCutout( bool on) {
|
// setCutout() for MAIN track
|
||||||
(void) on;
|
void TrackManager::setCutout( bool on,bool interruptContext) {
|
||||||
// TODO Cutout needs fake ports as well
|
//(void) on; // avoid compiler warning -Wunused
|
||||||
// TODO APPLY_BY_MODE(TRACK_MODE_MAIN,setCutout(on));
|
// Cutout needs fake ports as well
|
||||||
|
HAVE_PORTA(shadowPORTA=PORTA);
|
||||||
|
HAVE_PORTB(shadowPORTB=PORTB);
|
||||||
|
HAVE_PORTC(shadowPORTC=PORTC);
|
||||||
|
HAVE_PORTH(shadowPORTH=PORTH);
|
||||||
|
APPLY_BY_MODE(TRACK_MODE_MAIN,setBrake(on,interruptContext));
|
||||||
|
HAVE_PORTA(PORTA=shadowPORTA);
|
||||||
|
HAVE_PORTB(PORTB=shadowPORTB);
|
||||||
|
HAVE_PORTC(PORTC=shadowPORTC);
|
||||||
|
HAVE_PORTH(PORTH=shadowPORTH);
|
||||||
|
}
|
||||||
|
|
||||||
|
void TrackManager::setPROGCutout( bool on,bool interruptContext) {
|
||||||
|
HAVE_PORTA(shadowPORTA=PORTA);
|
||||||
|
HAVE_PORTB(shadowPORTB=PORTB);
|
||||||
|
HAVE_PORTC(shadowPORTC=PORTC);
|
||||||
|
HAVE_PORTH(shadowPORTH=PORTH);
|
||||||
|
APPLY_BY_MODE(TRACK_MODE_PROG,setBrake(on,interruptContext));
|
||||||
|
HAVE_PORTA(PORTA=shadowPORTA);
|
||||||
|
HAVE_PORTB(PORTB=shadowPORTB);
|
||||||
|
HAVE_PORTC(PORTC=shadowPORTC);
|
||||||
|
HAVE_PORTH(PORTH=shadowPORTH);
|
||||||
|
}
|
||||||
|
|
||||||
|
// true when there is any railcom capable MAIN track
|
||||||
|
bool TrackManager::isRailcomCapable() {
|
||||||
|
FOR_EACH_TRACK(t) {
|
||||||
|
if((track[t]->getMode()==TRACK_MODE_MAIN) && (track[t]->isRailcomCapable())){
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// setPROGSignal(), called from interrupt context
|
// setPROGSignal(), called from interrupt context
|
||||||
|
|
|
@ -51,9 +51,11 @@ class TrackManager {
|
||||||
);
|
);
|
||||||
|
|
||||||
static void setDCCSignal( bool on);
|
static void setDCCSignal( bool on);
|
||||||
static void setCutout( bool on);
|
|
||||||
static void setPROGSignal( bool on);
|
static void setPROGSignal( bool on);
|
||||||
static void setDCSignal(int16_t cab, byte speedbyte);
|
static void setDCSignal(int16_t cab, byte speedbyte);
|
||||||
|
static void setCutout( bool on,bool interruptContext=false);
|
||||||
|
static void setPROGCutout( bool on,bool interruptContext=false);
|
||||||
|
static bool isRailcomCapable();
|
||||||
static MotorDriver * getProgDriver();
|
static MotorDriver * getProgDriver();
|
||||||
#ifdef ARDUINO_ARCH_ESP32
|
#ifdef ARDUINO_ARCH_ESP32
|
||||||
static std::vector<MotorDriver *>getMainDrivers();
|
static std::vector<MotorDriver *>getMainDrivers();
|
||||||
|
|
Loading…
Reference in New Issue
Block a user