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

DCCTrack::schedulePacket allows multiple different motordrivers side by side

This commit is contained in:
Harald Barth 2021-11-22 23:26:04 +01:00
parent ed2aa4c1d8
commit c711be7980
14 changed files with 211 additions and 56 deletions

30
DCC.cpp
View File

@ -20,6 +20,7 @@
#include "DIAG.h"
#include "DCC.h"
#include "DCCWaveform.h"
#include "DCCTrack.h"
#include "EEStore.h"
#include "GITHUB_SHA.h"
#include "version.h"
@ -62,7 +63,13 @@ void DCC::begin() {
(void)EEPROM; // tell compiler not to warn this is unused
EEStore::init();
DCCWaveform::begin(mDC.mainTrack(),mDC.progTrack());
DCCWaveform::begin(mDC.mainTrack(),mDC.progTrack());
DCCTrack::mainTrack.addDriver(mDC.mainTrack());
DCCTrack::progTrack.addDriver(mDC.progTrack());
MotorDriver *md;
mDC.add(2, md = new MotorDriver(16, 21, UNUSED_PIN, UNUSED_PIN, UNUSED_PIN, 2.00, 2000, UNUSED_PIN, RMT_MAIN));
DCCTrack::mainTrack.addDriver(md);
}
void DCC::setJoinRelayPin(byte joinRelayPin) {
@ -118,7 +125,7 @@ void DCC::setThrottle2( uint16_t cab, byte speedCode) {
}
DCCWaveform::mainTrack.schedulePacket(b, nB, 0);
DCCTrack::mainTrack.schedulePacket(b, nB, 0);
}
void DCC::setFunctionInternal(int cab, byte byte1, byte byte2) {
@ -132,7 +139,7 @@ void DCC::setFunctionInternal(int cab, byte byte1, byte byte2) {
if (byte1!=0) b[nB++] = byte1;
b[nB++] = byte2;
DCCWaveform::mainTrack.schedulePacket(b, nB, 0);
DCCTrack::mainTrack.schedulePacket(b, nB, 0);
}
uint8_t DCC::getThrottleSpeed(int cab) {
@ -167,7 +174,7 @@ void DCC::setFn( int cab, int16_t functionNumber, bool on) {
b[nB++] = (functionNumber & 0x7F) | (on ? 0x80 : 0); // low order bits and state flag
b[nB++] = functionNumber >>7 ; // high order bits
}
DCCWaveform::mainTrack.schedulePacket(b, nB, 4);
DCCTrack::mainTrack.schedulePacket(b, nB, 3);
return;
}
@ -254,7 +261,7 @@ void DCC::setAccessory(int address, byte number, bool activate) {
b[0] = address % 64 + 128; // first byte is of the form 10AAAAAA, where AAAAAA represent 6 least signifcant bits of accessory address
b[1] = ((((address / 64) % 8) << 4) + (number % 4 << 1) + activate % 2) ^ 0xF8; // second byte is of the form 1AAACDDD, where C should be 1, and the least significant D represent activate/deactivate
DCCWaveform::mainTrack.schedulePacket(b, 2, 4); // Repeat the packet four times
DCCTrack::mainTrack.schedulePacket(b, 2, 3); // Repeat the packet four times (3 2 1 0)
}
//
@ -272,7 +279,7 @@ void DCC::writeCVByteMain(int cab, int cv, byte bValue) {
b[nB++] = cv2(cv);
b[nB++] = bValue;
DCCWaveform::mainTrack.schedulePacket(b, nB, 4);
DCCTrack::mainTrack.schedulePacket(b, nB, 3);
}
//
@ -293,7 +300,7 @@ void DCC::writeCVBitMain(int cab, int cv, byte bNum, bool bValue) {
b[nB++] = cv2(cv);
b[nB++] = WRITE_BIT | (bValue ? BIT_ON : BIT_OFF) | bNum;
DCCWaveform::mainTrack.schedulePacket(b, nB, 4);
DCCTrack::mainTrack.schedulePacket(b, nB, 3);
}
void DCC::setProgTrackSyncMain(bool on) {
@ -571,6 +578,7 @@ byte DCC::loopStatus=0;
void DCC::loop() {
DCCWaveform::loop(ackManagerProg!=NULL); // power overload checks
mDC.loop();
ackManagerLoop(); // maintain prog track ack manager
issueReminders();
}
@ -771,7 +779,7 @@ void DCC::ackManagerLoop() {
if (Diag::ACK) DIAG(F("W%d cv=%d bit=%d"),opcode==W1, ackManagerCv,ackManagerBitNum);
byte instruction = WRITE_BIT | (opcode==W1 ? BIT_ON : BIT_OFF) | ackManagerBitNum;
byte message[] = {cv1(BIT_MANIPULATE, ackManagerCv), cv2(ackManagerCv), instruction };
DCCWaveform::progTrack.schedulePacket(message, sizeof(message), PROG_REPEATS);
DCCTrack::progTrack.schedulePacket(message, sizeof(message), PROG_REPEATS);
DCCWaveform::progTrack.setAckPending();
callbackState=AFTER_WRITE;
}
@ -782,7 +790,7 @@ void DCC::ackManagerLoop() {
if (checkResets( RESET_MIN)) return;
if (Diag::ACK) DIAG(F("WB cv=%d value=%d"),ackManagerCv,ackManagerByte);
byte message[] = {cv1(WRITE_BYTE, ackManagerCv), cv2(ackManagerCv), ackManagerByte};
DCCWaveform::progTrack.schedulePacket(message, sizeof(message), PROG_REPEATS);
DCCTrack::progTrack.schedulePacket(message, sizeof(message), PROG_REPEATS);
DCCWaveform::progTrack.setAckPending();
callbackState=AFTER_WRITE;
}
@ -793,7 +801,7 @@ void DCC::ackManagerLoop() {
if (checkResets( RESET_MIN)) return;
if (Diag::ACK) DIAG(F("VB cv=%d value=%d"),ackManagerCv,ackManagerByte);
byte message[] = { cv1(VERIFY_BYTE, ackManagerCv), cv2(ackManagerCv), ackManagerByte};
DCCWaveform::progTrack.schedulePacket(message, sizeof(message), PROG_REPEATS);
DCCTrack::progTrack.schedulePacket(message, sizeof(message), PROG_REPEATS);
DCCWaveform::progTrack.setAckPending();
}
break;
@ -805,7 +813,7 @@ void DCC::ackManagerLoop() {
if (Diag::ACK) DIAG(F("V%d cv=%d bit=%d"),opcode==V1, ackManagerCv,ackManagerBitNum);
byte instruction = VERIFY_BIT | (opcode==V0?BIT_OFF:BIT_ON) | ackManagerBitNum;
byte message[] = {cv1(BIT_MANIPULATE, ackManagerCv), cv2(ackManagerCv), instruction };
DCCWaveform::progTrack.schedulePacket(message, sizeof(message), PROG_REPEATS);
DCCTrack::progTrack.schedulePacket(message, sizeof(message), PROG_REPEATS);
DCCWaveform::progTrack.setAckPending();
}
break;

View File

@ -22,6 +22,7 @@
#include "StringFormatter.h"
#include "DCCEXParser.h"
#include "DCCWaveform.h"
#include "DCCTrack.h"
#include "Turnouts.h"
#include "Outputs.h"
#include "Sensors.h"
@ -413,7 +414,7 @@ void DCCEXParser::parse(Print *stream, byte *com, RingStream * ringStream)
packet[i]=(byte)p[i+1];
if (Diag::CMD) DIAG(F("packet[%d]=%d (0x%x)"), i, packet[i], packet[i]);
}
(opcode=='M'?DCCWaveform::mainTrack:DCCWaveform::progTrack).schedulePacket(packet,params,3);
(opcode=='M'?DCCTrack::mainTrack:DCCTrack::progTrack).schedulePacket(packet,params,3);
}
return;

12
DCCPacket.h Normal file
View File

@ -0,0 +1,12 @@
#pragma once
const byte MAX_PACKET_SIZE = 5; // NMRA standard extended packets, payload size WITHOUT checksum.
class dccPacket {
public:
byte data[MAX_PACKET_SIZE+1]; // space for checksum if needed
byte length : 4; // future proof up to 15
byte repeat : 4; // hopefully 15 enough for ever
//byte priority : 2; // 0 repeats; 1 mobile function ; 2 accessory ; 3 mobile speed
};

View File

@ -131,15 +131,25 @@ void RMTChannel::RMTprefill() {
const byte transmitMask[] = {0x80, 0x40, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01};
bool RMTChannel::RMTfillData(const byte buffer[], byte byteCount, byte repeatCount=1) {
//bool RMTChannel::RMTfillData(const byte buffer[], byte byteCount, byte repeatCount=0) {
bool RMTChannel::RMTfillData(dccPacket packet) {
// dataReady: Signals to then interrupt routine. It is set when
// we have data in the channel buffer which can be copied out
// to the HW. dataRepeat on the other hand signals back to
// the caller of this function if the data has been sent enough
// times (0 to 3 means 1 to 4 times in total).
if (dataReady == true || dataRepeat > 0) // we have still old work to do
return false;
if (DATA_LEN(byteCount) > maxDataLen) // this would overun our allocated memory for data
return false; // something very broken, can not convert packet
if (DATA_LEN(packet.length) > maxDataLen) { // this would overun our allocated memory for data
DIAG(F("Can not convert DCC bytes # %d to DCC bits %d, buffer too small"), packet.length, maxDataLen);
return false; // something very broken, can not convert packet
}
byte *buffer = packet.data;
// convert bytes to RMT stream of "bits"
byte bitcounter = 0;
for(byte n=0; n<byteCount; n++) {
for(byte n=0; n<packet.length; n++) {
for(byte bit=0; bit<8; bit++) {
if (buffer[n] & transmitMask[bit])
setDCCBit1(data + bitcounter++);
@ -152,7 +162,7 @@ bool RMTChannel::RMTfillData(const byte buffer[], byte byteCount, byte repeatCou
setEOT(data + bitcounter++); // EOT marker
dataLen = bitcounter;
dataReady = true;
dataRepeat = repeatCount;
dataRepeat = packet.repeat+1; // repeatCount of 0 means send once
return true;
}

View File

@ -20,6 +20,7 @@
#pragma once
#include <Arduino.h>
#if defined(ARDUINO_ARCH_ESP32)
#include "DCCPacket.h"
#include "driver/rmt.h"
#include "soc/rmt_reg.h"
#include "soc/rmt_struct.h"
@ -34,7 +35,8 @@ class RMTChannel {
RMTChannel(byte pin, byte ch, byte plen);
void IRAM_ATTR RMTinterrupt();
void RMTprefill();
bool RMTfillData(const byte buffer[], byte byteCount, byte repeatCount);
bool RMTfillData(dccPacket packet);
//bool RMTfillData(const byte buffer[], byte byteCount, byte repeatCount);
static RMTChannel mainRMTChannel;
static RMTChannel progRMTChannel;

38
DCCTrack.cpp Normal file
View File

@ -0,0 +1,38 @@
#include "defines.h"
#include "DCCTrack.h"
#include "DIAG.h"
DCCTrack::DCCTrack(DCCWaveform *w) {
waveform = w;
}
void DCCTrack::schedulePacket(const byte buffer[], byte byteCount, byte repeats) {
dccPacket packet;
// add checksum now, makes stuff easier later
byte checksum = 0;
for (byte b = 0; b < byteCount; b++) {
checksum ^= buffer[b];
packet.data[b] = buffer[b];
}
packet.data[byteCount] = checksum;
packet.length = byteCount + 1;
packet.repeat = repeats;
schedulePacket(packet);
};
void DCCTrack::schedulePacket(dccPacket packet) {
bool once=true;
for (const auto& driver: mD) {
if (driver->type() == RMT_MAIN || driver->type() == RMT_PROG) {
//DIAG(F("DCCTrack::schedulePacket RMT l=%d d=%x"),packet.length, packet.data[0]);
driver->schedulePacket(packet);
}
if (driver->type() == TIMERINTERRUPT && waveform && once) {
//DIAG(F("DCCTrack::schedulePacket WAVE l=%d d=%x"),packet.length, packet.data[0]);
waveform->schedulePacket(packet);
once=false;
}
}
}

20
DCCTrack.h Normal file
View File

@ -0,0 +1,20 @@
#pragma once
#include <Arduino.h>
#include "DCCPacket.h"
#include "DCCWaveform.h"
class DCCTrack {
public:
DCCTrack(DCCWaveform *w);
void schedulePacket(const byte buffer[], byte byteCount, byte repeats);
void schedulePacket(dccPacket packet);
inline void addDriver(MotorDriver *m) { mD.push_back(m); };
static DCCTrack mainTrack;
static DCCTrack progTrack;
private:
DCCWaveform *waveform;
std::vector<MotorDriver *>mD;
};

View File

@ -22,6 +22,7 @@
#include "defines.h"
#include "DCCWaveform.h"
#include "DCCTrack.h"
#include "DCCTimer.h"
#include "DIAG.h"
#include "freeMemory.h"
@ -29,6 +30,9 @@
DCCWaveform DCCWaveform::mainTrack(PREAMBLE_BITS_MAIN, true);
DCCWaveform DCCWaveform::progTrack(PREAMBLE_BITS_PROG, false);
DCCTrack DCCTrack::mainTrack(&DCCWaveform::mainTrack);
DCCTrack DCCTrack::progTrack(&DCCWaveform::progTrack);
bool DCCWaveform::progTrackSyncMain=false;
bool DCCWaveform::progTrackBoosted=false;
int DCCWaveform::progTripValue=0;
@ -38,8 +42,6 @@ uint8_t DCCWaveform::trailingEdgeCounter=0;
void DCCWaveform::begin(MotorDriver * mainDriver, MotorDriver * progDriver) {
mainTrack.rmtPin = new RMTChannel(21, 0, PREAMBLE_BITS_MAIN);
mainTrack.motorDriver=mainDriver;
progTrack.motorDriver=progDriver;
progTripValue = progDriver->mA2raw(TRIP_CURRENT_PROG); // need only calculate once hence static
@ -62,11 +64,11 @@ volatile bool ackflag = 0;
void IRAM_ATTR DCCWaveform::loop(bool ackManagerActive) {
if (mainTrack.packetPendingRMT) {
mainTrack.rmtPin->RMTfillData(mainTrack.pendingPacket, mainTrack.pendingLength, mainTrack.pendingRepeats);
mainTrack.packetPendingRMT=false;
//if (mainTrack.packetPendingRMT) {
// mainTrack.rmtPin->RMTfillData(mainTrack.pendingPacket, mainTrack.pendingLength, mainTrack.pendingRepeats);
// mainTrack.packetPendingRMT=false;
// sentResetsSincePacket = 0 // later when progtrack
}
//}
#ifdef SLOW_ANALOG_READ
if (ackflag) {
@ -305,17 +307,17 @@ void IRAM_ATTR DCCWaveform::interrupt2() {
// Wait until there is no packet pending, then make this pending
void DCCWaveform::schedulePacket(const byte buffer[], byte byteCount, byte repeats) {
if (byteCount > MAX_PACKET_SIZE) return; // allow for chksum
if (byteCount > MAX_PACKET_SIZE+1) return; // has chksum
while (packetPending);
portENTER_CRITICAL(&timerMux);
byte checksum = 0;
//byte checksum = 0;
for (byte b = 0; b < byteCount; b++) {
checksum ^= buffer[b];
//checksum ^= buffer[b];
pendingPacket[b] = buffer[b];
}
// buffer is MAX_PACKET_SIZE but pendingPacket is one bigger
pendingPacket[byteCount] = checksum;
pendingLength = byteCount + 1;
//pendingPacket[byteCount] = checksum;
pendingLength = byteCount /*+ 1*/;
pendingRepeats = repeats;
packetPending = true;
packetPendingRMT = true;

View File

@ -28,10 +28,8 @@ const int POWER_SAMPLE_ON_WAIT = 100;
const int POWER_SAMPLE_OFF_WAIT = 1000;
const int POWER_SAMPLE_OVERLOAD_WAIT = 20;
// Number of preamble bits.
const int PREAMBLE_BITS_MAIN = 16;
const int PREAMBLE_BITS_PROG = 22;
const byte MAX_PACKET_SIZE = 5; // NMRA standard extended packets, payload size WITHOUT checksum.
//const byte MAX_PACKET_SIZE = 5; // NMRA standard extended packets, payload size WITHOUT checksum.
#include "DCCPacket.h"
// The WAVE_STATE enum is deliberately numbered because a change of order would be catastrophic
// to the transform array.
@ -81,6 +79,9 @@ class DCCWaveform {
}
return tripmA;
}
inline void schedulePacket(dccPacket packet) {
schedulePacket(packet.data, packet.length, packet.repeat);
};
void schedulePacket(const byte buffer[], byte byteCount, byte repeats);
volatile bool packetPending;
volatile bool packetPendingRMT;
@ -124,7 +125,6 @@ class DCCWaveform {
bool isMainTrack;
MotorDriver* motorDriver;
RMTChannel* rmtPin;
// Transmission controller
byte transmitPacket[MAX_PACKET_SIZE+1]; // +1 for checksum
byte transmitLength;

View File

@ -1 +1 @@
#define GITHUB_SHA "ESP32-motordriver-2021121-22:55"
#define GITHUB_SHA "ESP32-motordriver-2021122-23:21"

View File

@ -69,6 +69,10 @@ protected:
I2CRB requestBlock;
FSH *_deviceName;
#if defined(ARDUINO_ARCH_ESP32)
// workaround: Has somehow no min function for all types
static inline T min(T a, int b) { return a < b ? a : b; };
#endif
};
// Because class GPIOBase is a template, the implementation (below) must be contained within the same
@ -246,4 +250,4 @@ int GPIOBase<T>::_read(VPIN vpin) {
return (_portInputState & mask) ? 0 : 1; // Invert state (5v=0, 0v=1)
}
#endif
#endif

View File

@ -22,12 +22,6 @@
#include "IO_GPIOBase.h"
#if defined(ARDUINO_ARCH_ESP32) // min seems to be missing from that package
#ifndef min
#define min(a,b) ((a)<(b)?(a):(b))
#endif
#endif
class MCP23008 : public GPIOBase<uint8_t> {
public:
static void create(VPIN firstVpin, uint8_t nPins, uint8_t I2CAddress, int interruptPin=-1) {

View File

@ -31,22 +31,33 @@ bool MotorDriver::usePWM=false;
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) {
byte current_pin, float sense_factor, unsigned int trip_milliamps, byte fault_pin,
driverType dt) {
dtype = dt;
powerPin=power_pin;
getFastPin(F("POWER"),powerPin,fastPowerPin);
pinMode(powerPin, OUTPUT);
signalPin=signal_pin;
getFastPin(F("SIG"),signalPin,fastSignalPin);
pinMode(signalPin, OUTPUT);
signalPin2=signal_pin2;
if (signalPin2!=UNUSED_PIN) {
dualSignal=true;
getFastPin(F("SIG2"),signalPin2,fastSignalPin2);
pinMode(signalPin2, OUTPUT);
if (dtype == RMT_MAIN) {
signalPin=signal_pin;
#if defined(ARDUINO_ARCH_ESP32)
rmtChannel = new RMTChannel(signalPin, 0, PREAMBLE_BITS_MAIN);
#endif
dualSignal=false;
} else if (dtype == TIMERINTERRUPT) {
signalPin=signal_pin;
getFastPin(F("SIG"),signalPin,fastSignalPin);
pinMode(signalPin, OUTPUT);
signalPin2=signal_pin2;
if (signalPin2!=UNUSED_PIN) {
dualSignal=true;
getFastPin(F("SIG2"),signalPin2,fastSignalPin2);
pinMode(signalPin2, OUTPUT);
} else {
dualSignal=false;
}
}
else dualSignal=false;
brakePin=brake_pin;
if (brake_pin!=UNUSED_PIN){
@ -197,6 +208,21 @@ void MotorDriver::getFastPin(const FSH* type,int pin, bool input, FASTPIN & res
// DIAG(F(" port=0x%x, inoutpin=0x%x, isinput=%d, mask=0x%x"),port, result.inout,input,result.maskHIGH);
}
bool MotorDriver::schedulePacket(dccPacket packet) {
if(!rmtChannel) return true; // fake success if functionality is not there
outQueue.push(packet);
if (outQueue.size() > 10) {
DIAG(F("Warning: outQueue > 10"));
}
return true;
}
void MotorDriver::loop() {
if (rmtChannel && !outQueue.empty() && rmtChannel->RMTfillData(outQueue.front()))
outQueue.pop();
}
MotorDriverContainer::MotorDriverContainer(const FSH * motorShieldName,
MotorDriver *m0,
MotorDriver *m1,
@ -217,4 +243,15 @@ MotorDriverContainer::MotorDriverContainer(const FSH * motorShieldName,
shieldName = (FSH *)motorShieldName;
}
void MotorDriverContainer::loop() {
static byte i = 0;
// loops over MotorDrivers which have loop tasks
if (mD[i])
if (mD[i]->type() == RMT_MAIN || mD[i]->type() == RMT_PROG)
mD[i]->loop();
i++;
if(i > 7) i=0;
}
MotorDriverContainer mDC(MOTOR_SHIELD_TYPE);

View File

@ -16,12 +16,20 @@
* You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/
#ifndef MotorDriver_h
#define MotorDriver_h
#include "defines.h"
#include "FSH.h"
// Virtualised Motor shield 1-track hardware Interface
#if defined(ARDUINO_ARCH_ESP32)
#include <queue>
#include "DCCRMT.h"
#endif
// Number of preamble bits (moved here so MotorDriver and Waveform know)
const int PREAMBLE_BITS_MAIN = 16;
const int PREAMBLE_BITS_PROG = 22;
#ifndef UNUSED_PIN // sync define with the one in MotorDrivers.h
#define UNUSED_PIN 127 // inside int8_t
@ -48,10 +56,13 @@ struct FASTPIN {
#define isHIGH(fastpin) (*fastpin.inout & fastpin.maskHIGH)
#define isLOW(fastpin) (!isHIGH(fastpin))
enum driverType { TIMERINTERRUPT, RMT_MAIN, RMT_PROG, DC_ENA, DC_BRAKE };
class MotorDriver {
public:
MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, int8_t brake_pin,
byte current_pin, float senseFactor, unsigned int tripMilliamps, byte faultPin);
byte current_pin, float senseFactor, unsigned int tripMilliamps, byte faultPin,
driverType t=TIMERINTERRUPT);
void setPower( bool on);
void setSignal( bool high);
void setBrake( bool on);
@ -68,6 +79,12 @@ class MotorDriver {
inline byte getFaultPin() {
return faultPin;
}
#if defined(ARDUINO_ARCH_ESP32)
void loop();
inline driverType type() { return dtype; };
bool schedulePacket(dccPacket packet);
#endif
private:
void getFastPin(const FSH* type,int pin, bool input, FASTPIN & result);
void getFastPin(const FSH* type,int pin, FASTPIN & result) {
@ -92,6 +109,11 @@ class MotorDriver {
if (doit) __enable_irq();
}
#endif
#if defined(ARDUINO_ARCH_ESP32)
RMTChannel* rmtChannel;
std::queue<dccPacket> outQueue;
driverType dtype;
#endif
};
class MotorDriverContainer {
@ -105,10 +127,15 @@ public:
MotorDriver *m5=NULL,
MotorDriver *m6=NULL,
MotorDriver *m7=NULL);
inline void add(byte n, MotorDriver *m) {
if (n>8) return;
mD[n] = m;
};
// void SetCapability(byte n, byte cap, char [] name);
inline FSH *getMotorShieldName() { return shieldName; };
inline MotorDriver *mainTrack() { return mD[0]; }; //start fixed
inline MotorDriver *progTrack() { return mD[1]; };
void loop();
private:
MotorDriver *mD[8];