1
0
mirror of https://github.com/DCC-EX/CommandStation-EX.git synced 2025-07-29 02:13:45 +02:00

Compare commits

...

30 Commits

Author SHA1 Message Date
Colin Murdoch
ea4f90d5fc Merged in Power changes
Merge in power changes and EXRAIL command & update to version.h
2023-10-11 17:06:56 +01:00
Colin Murdoch
1181fd855d Merge branch 'devel-power-chm' into devel 2023-10-11 16:58:17 +01:00
Colin Murdoch
a092e06a6f Update .gitignore
added UserAddin.txt to gitignore
2023-10-10 12:11:49 +01:00
Colin Murdoch
68fd56e7fc Added returnDCAddr
Added function to return DC address
2023-10-10 11:52:46 +01:00
Asbelos
370dae0ab8 Merge branch 'master' into devel 2023-10-09 18:15:36 +01:00
Asbelos
bef4b2ec35 fix <JR> default roster 2023-10-09 18:09:48 +01:00
Colin Murdoch
fe618d0b85 Add getModeName()
Add facility to get the name of the track mode
2023-10-06 19:11:11 +01:00
pmantoine
2ff1619ad1 STM32 reinstate 100% duty cycle PWM 2023-10-04 14:54:06 +08:00
pmantoine
7afd4443d6 STM32 revised I2C clock setup 2023-10-02 12:04:47 +08:00
Colin Murdoch
52cfc18754 Remove Diags not needed
Tidy up Diags and responses - use HASH_KEYWORD in place of 'A'
2023-09-28 15:02:30 +01:00
pmantoine
ed0cfee091 STM32 DCCEXanalogWrite for TrackManager PWM 2023-09-28 17:43:22 +08:00
Colin Murdoch
25bbfa4c68 Fix <1 JOIN>
Fixed <1 JOIN> issue in TrackManager
2023-09-27 14:46:48 +01:00
Colin Murdoch
2a46b96083 Updates to power
Updates to powere routines and EXRAIL
2023-09-26 18:02:39 +01:00
Colin Murdoch
17c004aecf Code corrections
code corrections
2023-09-25 14:32:54 +01:00
Colin Murdoch
9e3ae21bb8 Change to EXRAIL Set_Power
Change to EXRAIL SET_Power
2023-09-25 09:59:17 +01:00
Harald Barth
624656ebc9 date tag 2023-09-24 20:56:27 +02:00
Harald Barth
5a7f278b1e correct return when requesting D RAM 2023-09-24 20:55:16 +02:00
Harald Barth
9333beda49 correct return when requesting D RAM 2023-09-24 20:54:17 +02:00
Colin Murdoch
aacb980dc8 Power control plus EXRAIL
Power Control <0 A> etc plus EXRAIL SET_POWER
Not yet fully tested.
2023-09-24 15:40:42 +01:00
Colin Murdoch
8052090e0f Added Single Track Power On/Off
Added power On/Off <> commands
2023-09-22 17:03:40 +01:00
Harald Barth
46289fa78c Check bad AT firmware version 2023-09-14 09:05:23 +02:00
Harald Barth
b3cafd126e sample file corrections 2023-08-30 23:26:20 +02:00
Harald Barth
c55fa9f9d2 version number update 2023-08-25 19:08:58 +02:00
Harald Barth
210d96a3e3 Bugfix: ESP32 30ms off time 2023-08-25 19:07:57 +02:00
Harald Barth
42f3c7c128 version number update 2023-08-24 10:05:31 +02:00
Harald Barth
6cd7002e91 Bugfix: execute 30ms off time before rejoin 2023-08-24 10:03:29 +02:00
peteGSX
085762e800 Add OPCODE list to DCCEXParser.cpp 2023-08-18 18:52:34 +10:00
Harald Barth
2db2b0ecc6 Committing a SHA 2023-08-07 20:27:22 +02:00
Harald Barth
fd58a749ef Committing a SHA 2023-08-07 20:25:14 +02:00
Harald Barth
3bddf4dfd1 Make 4.2.69 the 5.0.0 release 2023-08-07 19:45:45 +02:00
17 changed files with 521 additions and 153 deletions

2
.gitignore vendored
View File

@@ -13,3 +13,5 @@ myFilter.cpp
my*.h
!my*.example.h
compile_commands.json
newcode.txt.old
UserAddin.txt

View File

@@ -269,6 +269,6 @@ void CommandDistributor::broadcastRaw(clientType type, char * msg) {
broadcastReply(type, F("%s"),msg);
}
void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr) {
broadcastReply(COMMAND_TYPE, format,trackLetter,dcAddr);
void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr) {
broadcastReply(COMMAND_TYPE, format,trackLetter, dcAddr);
}

View File

@@ -55,7 +55,7 @@ public :
static int16_t retClockTime();
static void broadcastPower();
static void broadcastRaw(clientType type,char * msg);
static void broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr);
static void broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr);
template<typename... Targs> static void broadcastReply(clientType type, Targs... msg);
static void forget(byte clientId);

View File

@@ -122,7 +122,7 @@ Once a new OPCODE is decided upon, update this list.
for (int16_t i=0;;i+=sizeof(flashList[0])) { \
int16_t value=GETHIGHFLASHW(flashList,i); \
if (value==INT16_MAX) break; \
if (value != 0) StringFormatter::send(stream,F(" %d"),value); \
StringFormatter::send(stream,F(" %d"),value); \
}
@@ -157,6 +157,7 @@ const int16_t HASH_KEYWORD_VPIN=-415;
const int16_t HASH_KEYWORD_A='A';
const int16_t HASH_KEYWORD_C='C';
const int16_t HASH_KEYWORD_G='G';
const int16_t HASH_KEYWORD_H='H';
const int16_t HASH_KEYWORD_I='I';
const int16_t HASH_KEYWORD_O='O';
const int16_t HASH_KEYWORD_P='P';
@@ -552,69 +553,131 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
case '1': // POWERON <1 [MAIN|PROG|JOIN]>
{
bool main=false;
bool prog=false;
bool join=false;
if (params > 1) break;
if (params==0) { // All
main=true;
prog=true;
}
if (params==1) {
if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN>
main=true;
}
bool main=false;
bool prog=false;
bool join=false;
bool singletrack=false;
//byte t=0;
if (params > 1) break;
if (params==0) { // All
main=true;
prog=true;
}
if (params==1) {
if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN>
main=true;
}
#ifndef DISABLE_PROG
else if (p[0] == HASH_KEYWORD_JOIN) { // <1 JOIN>
main=true;
prog=true;
join=true;
}
else if (p[0]==HASH_KEYWORD_PROG) { // <1 PROG>
prog=true;
}
else if (p[0] == HASH_KEYWORD_JOIN) { // <1 JOIN>
main=true;
prog=true;
join=true;
}
else if (p[0]==HASH_KEYWORD_PROG) { // <1 PROG>
prog=true;
}
#endif
else break; // will reply <X>
}
TrackManager::setJoin(join);
if (main) TrackManager::setMainPower(POWERMODE::ON);
if (prog) TrackManager::setProgPower(POWERMODE::ON);
//else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H>
else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H>
byte t = (p[0] - 'A');
//DIAG(F("Processing track - %d "), t);
if (TrackManager::isProg(t)) {
main = false;
prog = true;
}
else
{
main=true;
prog=false;
}
singletrack=true;
if (main) TrackManager::setTrackPower(false, false, POWERMODE::ON, t);
if (prog) TrackManager::setTrackPower(true, false, POWERMODE::ON, t);
StringFormatter::send(stream, F("<1 %c>\n"), t+'A');
//CommandDistributor::broadcastPower();
//TrackManager::streamTrackState(NULL,t);
return;
}
CommandDistributor::broadcastPower();
return;
else break; // will reply <X>
}
if (!singletrack) {
TrackManager::setJoin(join);
if (join) TrackManager::setJoinPower(POWERMODE::ON);
else {
if (main) TrackManager::setMainPower(POWERMODE::ON);
if (prog) TrackManager::setProgPower(POWERMODE::ON);
}
CommandDistributor::broadcastPower();
return;
}
}
case '0': // POWEROFF <0 [MAIN | PROG] >
{
bool main=false;
bool prog=false;
if (params > 1) break;
if (params==0) { // All
main=true;
prog=true;
}
if (params==1) {
if (p[0]==HASH_KEYWORD_MAIN) { // <0 MAIN>
main=true;
}
bool main=false;
bool prog=false;
bool singletrack=false;
//byte t=0;
if (params > 1) break;
if (params==0) { // All
main=true;
prog=true;
}
if (params==1) {
if (p[0]==HASH_KEYWORD_MAIN) { // <0 MAIN>
main=true;
}
#ifndef DISABLE_PROG
else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG>
prog=true;
}
else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG>
prog=true;
}
#endif
else break; // will reply <X>
}
//else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H>
else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H>
byte t = (p[0] - 'A');
//DIAG(F("Processing track - %d "), t);
if (TrackManager::isProg(t)) {
main = false;
prog = true;
}
else
{
main=true;
prog=false;
}
singletrack=true;
TrackManager::setJoin(false);
if (main) TrackManager::setTrackPower(false, false, POWERMODE::OFF, t);
if (prog) {
TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off
TrackManager::setTrackPower(true, false, POWERMODE::OFF, t);
}
StringFormatter::send(stream, F("<0 %c>\n"), t+'A');
//CommandDistributor::broadcastPower();
//TrackManager::streamTrackState(NULL, t);
return;
}
TrackManager::setJoin(false);
if (main) TrackManager::setMainPower(POWERMODE::OFF);
if (prog) {
TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off
TrackManager::setProgPower(POWERMODE::OFF);
}
else break; // will reply <X>
}
CommandDistributor::broadcastPower();
return;
if (!singletrack) {
TrackManager::setJoin(false);
if (main) TrackManager::setMainPower(POWERMODE::OFF);
if (prog) {
TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off
TrackManager::setProgPower(POWERMODE::OFF);
}
CommandDistributor::broadcastPower();
return;
}
}
case '!': // ESTOP ALL <!>
DCC::setThrottle(0,1,1); // this broadcasts speed 1(estop) and sets all reminders to speed 1.
@@ -1057,7 +1120,7 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
case HASH_KEYWORD_RAM: // <D RAM>
StringFormatter::send(stream, F("Free memory=%d\n"), DCCTimer::getMinimumFreeMemory());
break;
return true;
#ifndef DISABLE_PROG
case HASH_KEYWORD_ACK: // <D ACK ON/OFF> <D ACK [LIMIT|MIN|MAX|RETRY] Value>

View File

@@ -1,6 +1,6 @@
/*
* © 2023 Neil McKechnie
* © 2022-23 Paul M. Antoine
* © 2022-2023 Paul M. Antoine
* © 2021 Mike S
* © 2021, 2023 Harald Barth
* © 2021 Fred Decker
@@ -154,13 +154,28 @@ HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6
///////////////////////////////////////////////////////////////////////////////////////////////
INTERRUPT_CALLBACK interruptHandler=0;
// Let's use STM32's timer #11 until disabused of this notion
// Timer #11 is used for "servo" library, but as DCC-EX is not using
// this libary, we should be free and clear.
HardwareTimer timer(TIM11);
// On STM32F4xx models that have them, Timers 6 and 7 have no PWM output capability,
// so are good choices for general timer duties - they are used for tone and servo
// in stm32duino so we shall usurp those as DCC-EX doesn't use tone or servo libs.
// NB: the F401, F410 and F411 do **not** have Timer 6 or 7, so we use Timer 11
#ifndef DCC_EX_TIMER
#if defined(TIM6)
#define DCC_EX_TIMER TIM6
#elif defined(TIM7)
#define DCC_EX_TIMER TIM7
#elif defined(TIM11)
#define DCC_EX_TIMER TIM11
#else
#warning This STM32F4XX variant does not have Timers 6,7 or 11!!
#endif
#endif // ifndef DCC_EX_TIMER
HardwareTimer dcctimer(DCC_EX_TIMER);
void DCCTimer_Handler() __attribute__((interrupt));
// Timer IRQ handler
void Timer11_Handler() {
void DCCTimer_Handler() {
interruptHandler();
}
@@ -168,22 +183,24 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
interruptHandler=callback;
noInterrupts();
// adc_set_sample_rate(ADC_SAMPLETIME_480CYCLES);
timer.pause();
timer.setPrescaleFactor(1);
dcctimer.pause();
dcctimer.setPrescaleFactor(1);
// timer.setOverflow(CLOCK_CYCLES * 2);
timer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT);
timer.attachInterrupt(Timer11_Handler);
timer.refresh();
timer.resume();
dcctimer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT);
// dcctimer.attachInterrupt(Timer11_Handler);
dcctimer.attachInterrupt(DCCTimer_Handler);
dcctimer.setInterruptPriority(0, 0); // Set highest preemptive priority!
dcctimer.refresh();
dcctimer.resume();
interrupts();
}
bool DCCTimer::isPWMPin(byte pin) {
//TODO: SAMD whilst this call to digitalPinHasPWM will reveal which pins can do PWM,
//TODO: STM32 whilst this call to digitalPinHasPWM will reveal which pins can do PWM,
// there's no support yet for High Accuracy, so for now return false
// return digitalPinHasPWM(pin);
(void) pin;
return false;
}
@@ -235,6 +252,78 @@ void DCCTimer::reset() {
while(true) {};
}
// TODO: rationalise the size of these... could really use sparse arrays etc.
static HardwareTimer * pin_timer[100] = {0};
static uint32_t channel_frequency[100] = {0};
static uint32_t pin_channel[100] = {0};
// Using the HardwareTimer library API included in stm32duino core to handle PWM duties
// TODO: in order to use the HA code above which Neil kindly wrote, we may have to do something more
// sophisticated about detecting any clash between the timer we'd like to use for PWM and the ones
// currently used for HA so they don't interfere with one another. For now we'll just make PWM
// work well... then work backwards to integrate with HA mode if we can.
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency)
{
if (pin_timer[pin] == NULL) {
// Automatically retrieve TIM instance and channel associated to pin
// This is used to be compatible with all STM32 series automatically.
TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pin), PinMap_PWM);
if (Instance == NULL) {
// We shouldn't get here (famous last words) as it ought to have been caught by brakeCanPWM()!
DIAG(F("DCCEXanalogWriteFrequency::Pin %d has no PWM function!"), pin);
return;
}
pin_channel[pin] = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pin), PinMap_PWM));
// Instantiate HardwareTimer object. Thanks to 'new' instantiation,
// HardwareTimer is not destructed when setup function is finished.
pin_timer[pin] = new HardwareTimer(Instance);
// Configure and start PWM
// MyTim->setPWM(channel, pin, 5, 10, NULL, NULL); // No callback required, we can simplify the function call
if (pin_timer[pin] != NULL)
{
pin_timer[pin]->setPWM(pin_channel[pin], pin, frequency, 0); // set frequency in Hertz, 0% dutycycle
DIAG(F("DCCEXanalogWriteFrequency::Pin %d on Timer %d, frequency %d"), pin, pin_channel[pin], frequency);
}
else
DIAG(F("DCCEXanalogWriteFrequency::failed to allocate HardwareTimer instance!"));
}
else
{
// Frequency change request
if (frequency != channel_frequency[pin])
{
pinmap_pinout(digitalPinToPinName(pin), PinMap_TIM); // ensure the pin has been configured!
pin_timer[pin]->setOverflow(frequency, HERTZ_FORMAT); // Just change the frequency if it's already running!
DIAG(F("DCCEXanalogWriteFrequency::setting frequency to %d"), frequency);
}
}
channel_frequency[pin] = frequency;
return;
}
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
// Calculate percentage duty cycle from value given
uint32_t duty_cycle = (value * 100 / 256) + 1;
if (pin_timer[pin] != NULL) {
// if (duty_cycle == 100)
// {
// pin_timer[pin]->pauseChannel(pin_channel[pin]);
// DIAG(F("DCCEXanalogWrite::Pausing timer channel on pin %d"), pin);
// }
// else
// {
pinmap_pinout(digitalPinToPinName(pin), PinMap_TIM); // ensure the pin has been configured!
// pin_timer[pin]->resumeChannel(pin_channel[pin]);
pin_timer[pin]->setCaptureCompare(pin_channel[pin], duty_cycle, PERCENT_COMPARE_FORMAT); // DCC_EX_PWM_FREQ Hertz, duty_cycle% dutycycle
DIAG(F("DCCEXanalogWrite::Pin %d, value %d, duty cycle %d"), pin, value, duty_cycle);
// }
}
else
DIAG(F("DCCEXanalogWrite::Pin %d is not configured for PWM!"), pin);
}
// Now we can handle more ADCs, maybe this works!
#define NUM_ADC_INPUTS NUM_ANALOG_INPUTS

View File

@@ -780,6 +780,20 @@ void RMFT2::loop2() {
TrackManager::setJoin(false);
CommandDistributor::broadcastPower();
break;
case OPCODE_SET_POWER:
// operand is TRACK_POWER , trackid
//byte thistrack=getOperand(1);
switch (operand) {
case TRACK_POWER_0:
TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), false, POWERMODE::OFF, getOperand(1));
break;
case TRACK_POWER_1:
TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), false, POWERMODE::ON, getOperand(1));
break;
}
break;
case OPCODE_SET_TRACK:
// operand is trackmode<<8 | track id

View File

@@ -59,7 +59,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,
OPCODE_ROSTER,OPCODE_KILLALL,
OPCODE_ROUTE,OPCODE_AUTOMATION,OPCODE_SEQUENCE,
OPCODE_ENDTASK,OPCODE_ENDEXRAIL,
OPCODE_SET_TRACK,
OPCODE_SET_TRACK,OPCODE_SET_POWER,
OPCODE_ONRED,OPCODE_ONAMBER,OPCODE_ONGREEN,
OPCODE_ONCHANGE,
OPCODE_ONCLOCKTIME,

View File

@@ -138,6 +138,7 @@
#undef SERVO_SIGNAL
#undef SET
#undef SET_TRACK
#undef SET_POWER
#undef SETLOCO
#undef SIGNAL
#undef SIGNALH
@@ -275,6 +276,7 @@
#define SERVO_TURNOUT(id,pin,activeAngle,inactiveAngle,profile,description...)
#define SET(pin)
#define SET_TRACK(track,mode)
#define SET_POWER(track,onoff)
#define SETLOCO(loco)
#define SIGNAL(redpin,amberpin,greenpin)
#define SIGNALH(redpin,amberpin,greenpin)

View File

@@ -63,6 +63,11 @@
// (10#mins)%100)
#define STRIP_ZERO(value) 10##value%100
// These constants help EXRAIL macros convert Track Power e.g. SET_POWER(A ON|OFF).
//const byte TRACK_POWER_0=0, TRACK_POWER_OFF=0;
//const byte TRACK_POWER_1=1, TRACK_POWER_ON=1;
// Pass 1 Implements aliases
#include "EXRAIL2MacroReset.h"
#undef ALIAS
@@ -407,11 +412,12 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = {
#define SERVO_TURNOUT(id,pin,activeAngle,inactiveAngle,profile,description...) OPCODE_SERVOTURNOUT,V(id),OPCODE_PAD,V(pin),OPCODE_PAD,V(activeAngle),OPCODE_PAD,V(inactiveAngle),OPCODE_PAD,V(PCA9685::ProfileType::profile),
#define SET(pin) OPCODE_SET,V(pin),
#define SET_TRACK(track,mode) OPCODE_SET_TRACK,V(TRACK_MODE_##mode <<8 | TRACK_NUMBER_##track),
#define SET_POWER(track,onoff) OPCODE_SET_POWER,V(TRACK_POWER_##onoff),OPCODE_PAD, V(TRACK_NUMBER_##track),
#define SETLOCO(loco) OPCODE_SETLOCO,V(loco),
#define SIGNAL(redpin,amberpin,greenpin)
#define SIGNALH(redpin,amberpin,greenpin)
#define SPEED(speed) OPCODE_SPEED,V(speed),
#define START(route) OPCODE_START,V(route),
#define START(route) OPCODE_START,V(route),
#define STOP OPCODE_SPEED,V(0),
#define THROW(id) OPCODE_THROW,V(id),
#ifndef IO_NO_HAL

View File

@@ -1 +1 @@
#define GITHUB_SHA "devel-202308302157Z"
#define GITHUB_SHA "devel-202309241855Z"

View File

@@ -117,35 +117,46 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) {
// Disable the I2C device, as TRISE can only be programmed whilst disabled
s->CR1 &= ~(I2C_CR1_PE); // Disable I2C
s->CR1 |= I2C_CR1_SWRST; // reset the I2C
asm("nop"); // wait a bit... suggestion from online!
s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation
if (i2cClockSpeed > 100000L)
if (i2cClockSpeed > 100000UL)
{
if (i2cClockSpeed > 400000L)
i2cClockSpeed = 400000L;
// if (i2cClockSpeed > 400000L)
// i2cClockSpeed = 400000L;
t_rise = 300; // nanoseconds
}
else
{
i2cClockSpeed = 100000L;
// i2cClockSpeed = 100000L;
t_rise = 1000; // nanoseconds
}
// Configure the rise time register
s->TRISE = (t_rise / (1000 / i2c_MHz)) + 1;
// Configure the rise time register - max allowed tRISE is 1000ns,
// so value = 1000ns * I2C_PERIPH_CLK MHz / 1000 + 1.
s->TRISE = (t_rise * i2c_MHz / 1000) + 1;
// Bit 15: I2C Master mode, 0=standard, 1=Fast Mode
// Bit 14: Duty, fast mode duty cycle (use 2:1)
// Bit 11-0: FREQR
if (i2cClockSpeed > 100000L) {
// In fast mode, I2C period is 3 * CCR * TPCLK1.
//APB1clk1 / 3 / i2cClockSpeed = 38, but that results in 306KHz not 400!
ccr_freq = 30; // So 30 gives 396KHz or so!
s->CCR = (uint16_t)(ccr_freq | 0x8000); // We need Fast Mode set
} else {
// In standard mode, I2C period is 2 * CCR * TPCLK1
ccr_freq = (APB1clk1 / 2 / i2cClockSpeed); // Should be 225 for 45Mhz APB1 clock
s->CCR |= (uint16_t)ccr_freq;
}
// if (i2cClockSpeed > 400000UL) {
// // In fast mode plus, I2C period is 3 * CCR * TPCLK1.
// // s->CCR &= ~(0x3000); // Clear all bits except 12 and 13 which must remain per reset value
// s->CCR = APB1clk1 / 3 / i2cClockSpeed; // Set I2C clockspeed to start!
// s->CCR |= 0xC000; // We need Fast Mode AND DUTY bits set
// } else {
// In standard and fast mode, I2C period is 2 * CCR * TPCLK1
s->CCR &= ~(0x3000); // Clear all bits except 12 and 13 which must remain per reset value
s->CCR |= (APB1clk1 / 2 / i2cClockSpeed); // Set I2C clockspeed to start!
// s->CCR |= (i2c_MHz * 500 / (i2cClockSpeed / 1000)); // Set I2C clockspeed to start!
// if (i2cClockSpeed > 100000UL)
// s->CCR |= 0xC000; // We need Fast Mode bits set as well
// }
// DIAG(F("I2C_init() peripheral clock is now: %d, full reg is %x"), (s->CR2 & 0xFF), s->CR2);
// DIAG(F("I2C_init() peripheral CCR is now: %d"), s->CCR);
// DIAG(F("I2C_init() peripheral TRISE is now: %d"), s->TRISE);
// Enable the I2C master mode
s->CR1 |= I2C_CR1_PE; // Enable I2C
@@ -159,6 +170,7 @@ void I2CManagerClass::I2C_init()
// Query the clockspeed from the STM32 HAL layer
APB1clk1 = HAL_RCC_GetPCLK1Freq();
i2c_MHz = APB1clk1 / 1000000UL;
// DIAG(F("I2C_init() peripheral clock speed is: %d"), i2c_MHz);
// Enable clocks
RCC->APB1ENR |= RCC_APB1ENR_I2C1EN;//(1 << 21); // Enable I2C CLOCK
// Reset the I2C1 peripheral to initial state
@@ -181,6 +193,7 @@ void I2CManagerClass::I2C_init()
GPIOB->AFR[1] |= (4<<0) | (4<<4); // PB8 on low nibble, PB9 on next nibble up
// Software reset the I2C peripheral
I2C1->CR1 &= ~I2C_CR1_PE; // Disable I2C1 peripheral
s->CR1 |= I2C_CR1_SWRST; // reset the I2C
asm("nop"); // wait a bit... suggestion from online!
s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation
@@ -191,6 +204,7 @@ void I2CManagerClass::I2C_init()
// Set I2C peripheral clock frequency
// s->CR2 |= I2C_PERIPH_CLK;
s->CR2 |= i2c_MHz;
// DIAG(F("I2C_init() peripheral clock is now: %d"), s->CR2);
// set own address to 00 - not used in master mode
I2C1->OAR1 = (1 << 14); // bit 14 should be kept at 1 according to the datasheet
@@ -214,6 +228,7 @@ void I2CManagerClass::I2C_init()
s->CR2 |= (I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN); // Enable Buffer, Event and Error interrupts
#endif
// DIAG(F("I2C_init() setting initial I2C clock to 100KHz"));
// Calculate baudrate and set default rate for now
// Configure the Clock Control Register for 100KHz SCL frequency
// Bit 15: I2C Master mode, 0=standard, 1=Fast Mode
@@ -221,12 +236,14 @@ void I2CManagerClass::I2C_init()
// Bit 11-0: so CCR divisor would be clk / 2 / 100000 (where clk is in Hz)
// s->CCR = I2C_PERIPH_CLK * 5;
s->CCR &= ~(0x3000); // Clear all bits except 12 and 13 which must remain per reset value
s->CCR |= (APB1clk1 / 2 / 100000UL); // i2c_MHz * 5;
// s->CCR = i2c_MHz * 5;
s->CCR |= (APB1clk1 / 2 / 100000UL); // Set a default of 100KHz I2C clockspeed to start!
// Configure the rise time register - max allowed is 1000ns, so value = 1000ns * I2C_PERIPH_CLK MHz / 1000 + 1.
// s->TRISE = I2C_PERIPH_CLK + 1; // 1000 ns / 50 ns = 20 + 1 = 21
s->TRISE = i2c_MHz + 1;
s->TRISE = (1000 * i2c_MHz / 1000) + 1;
// DIAG(F("I2C_init() peripheral clock is now: %d, full reg is %x"), (s->CR2 & 0xFF), s->CR2);
// DIAG(F("I2C_init() peripheral CCR is now: %d"), s->CCR);
// DIAG(F("I2C_init() peripheral TRISE is now: %d"), s->TRISE);
// Enable the I2C master mode
s->CR1 |= I2C_CR1_PE; // Enable I2C

View File

@@ -34,6 +34,11 @@ unsigned long MotorDriver::globalOverloadStart = 0;
volatile portreg_t shadowPORTA;
volatile portreg_t shadowPORTB;
volatile portreg_t shadowPORTC;
#if defined(ARDUINO_ARCH_STM32)
volatile portreg_t shadowPORTD;
volatile portreg_t shadowPORTE;
volatile portreg_t shadowPORTF;
#endif
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) {
@@ -68,6 +73,21 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
fastSignalPin.shadowinout = fastSignalPin.inout;
fastSignalPin.inout = &shadowPORTC;
}
if (HAVE_PORTD(fastSignalPin.inout == &PORTD)) {
DIAG(F("Found PORTD pin %d"),signalPin);
fastSignalPin.shadowinout = fastSignalPin.inout;
fastSignalPin.inout = &shadowPORTD;
}
if (HAVE_PORTE(fastSignalPin.inout == &PORTE)) {
DIAG(F("Found PORTE pin %d"),signalPin);
fastSignalPin.shadowinout = fastSignalPin.inout;
fastSignalPin.inout = &shadowPORTE;
}
if (HAVE_PORTF(fastSignalPin.inout == &PORTF)) {
DIAG(F("Found PORTF pin %d"),signalPin);
fastSignalPin.shadowinout = fastSignalPin.inout;
fastSignalPin.inout = &shadowPORTF;
}
signalPin2=signal_pin2;
if (signalPin2!=UNUSED_PIN) {
@@ -91,6 +111,21 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
fastSignalPin2.shadowinout = fastSignalPin2.inout;
fastSignalPin2.inout = &shadowPORTC;
}
if (HAVE_PORTD(fastSignalPin2.inout == &PORTD)) {
DIAG(F("Found PORTD pin %d"),signalPin2);
fastSignalPin2.shadowinout = fastSignalPin2.inout;
fastSignalPin2.inout = &shadowPORTD;
}
if (HAVE_PORTE(fastSignalPin2.inout == &PORTE)) {
DIAG(F("Found PORTE pin %d"),signalPin2);
fastSignalPin2.shadowinout = fastSignalPin2.inout;
fastSignalPin2.inout = &shadowPORTE;
}
if (HAVE_PORTF(fastSignalPin2.inout == &PORTF)) {
DIAG(F("Found PORTF pin %d"),signalPin2);
fastSignalPin2.shadowinout = fastSignalPin2.inout;
fastSignalPin2.inout = &shadowPORTF;
}
}
else dualSignal=false;
@@ -279,7 +314,7 @@ void MotorDriver::startCurrentFromHW() {
#pragma GCC pop_options
#endif //ANALOG_READ_INTERRUPT
#if defined(ARDUINO_ARCH_ESP32)
#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32)
#ifdef VARIABLE_TONES
uint16_t taurustones[28] = { 165, 175, 196, 220,
247, 262, 294, 330,
@@ -330,7 +365,7 @@ void MotorDriver::setDCSignal(byte speedcode) {
byte tSpeed=speedcode & 0x7F; // DCC Speed with 0,1 stop and speed steps 2 to 127
byte tDir=speedcode & 0x80;
byte brake;
#if defined(ARDUINO_ARCH_ESP32)
#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32)
{
int f = 131;
#ifdef VARIABLE_TONES
@@ -348,7 +383,7 @@ void MotorDriver::setDCSignal(byte speedcode) {
else brake = 2 * (128-tSpeed);
if (invertBrake)
brake=255-brake;
#if defined(ARDUINO_ARCH_ESP32)
#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32)
DCCTimer::DCCEXanalogWrite(brakePin,brake);
#else
analogWrite(brakePin,brake);
@@ -372,6 +407,24 @@ void MotorDriver::setDCSignal(byte speedcode) {
setSignal(tDir);
HAVE_PORTC(PORTC=shadowPORTC);
interrupts();
} else if (HAVE_PORTD(fastSignalPin.shadowinout == &PORTD)) {
noInterrupts();
HAVE_PORTD(shadowPORTD=PORTD);
setSignal(tDir);
HAVE_PORTD(PORTD=shadowPORTD);
interrupts();
} else if (HAVE_PORTE(fastSignalPin.shadowinout == &PORTE)) {
noInterrupts();
HAVE_PORTE(shadowPORTE=PORTE);
setSignal(tDir);
HAVE_PORTE(PORTE=shadowPORTE);
interrupts();
} else if (HAVE_PORTF(fastSignalPin.shadowinout == &PORTF)) {
noInterrupts();
HAVE_PORTF(shadowPORTF=PORTF);
setSignal(tDir);
HAVE_PORTF(PORTF=shadowPORTF);
interrupts();
} else {
noInterrupts();
setSignal(tDir);
@@ -393,6 +446,13 @@ void MotorDriver::throttleInrush(bool on) {
} else {
ledcDetachPin(brakePin);
}
#elif defined(ARDUINO_ARCH_STM32)
if(on) {
DCCTimer::DCCEXanalogWriteFrequency(brakePin, 62500);
DCCTimer::DCCEXanalogWrite(brakePin,duty);
} else {
pinMode(brakePin, OUTPUT);
}
#else
if(on){
switch(brakePin) {

View File

@@ -1,5 +1,5 @@
/*
* © 2022 Paul M Antoine
* © 2022-2023 Paul M. Antoine
* © 2021 Mike S
* © 2021 Fred Decker
* © 2020 Chris Harlow
@@ -60,6 +60,16 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO
#define HAVE_PORTB(X) X
#define PORTC GPIOC->ODR
#define HAVE_PORTC(X) X
#define PORTD GPIOD->ODR
#define HAVE_PORTD(X) X
#if defined(GPIOE)
#define PORTE GPIOE->ODR
#define HAVE_PORTE(X) X
#endif
#if defined(GPIOF)
#define PORTF GPIOF->ODR
#define HAVE_PORTF(X) X
#endif
#endif
// if macros not defined as pass-through we define
@@ -74,6 +84,15 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO
#ifndef HAVE_PORTC
#define HAVE_PORTC(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
#endif
#ifndef HAVE_PORTD
#define HAVE_PORTD(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
#endif
#ifndef HAVE_PORTE
#define HAVE_PORTE(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
#endif
#ifndef HAVE_PORTF
#define HAVE_PORTF(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0
#endif
// Virtualised Motor shield 1-track hardware Interface
@@ -110,6 +129,9 @@ struct FASTPIN {
extern volatile portreg_t shadowPORTA;
extern volatile portreg_t shadowPORTB;
extern volatile portreg_t shadowPORTC;
extern volatile portreg_t shadowPORTD;
extern volatile portreg_t shadowPORTE;
extern volatile portreg_t shadowPORTF;
enum class POWERMODE : byte { OFF, ON, OVERLOAD, ALERT };
@@ -163,16 +185,16 @@ class MotorDriver {
unsigned int raw2mA( int raw);
unsigned int mA2raw( unsigned int mA);
inline bool brakeCanPWM() {
#if defined(ARDUINO_ARCH_ESP32) || defined(__arm__)
// TODO: on ARM we can use digitalPinHasPWM, and may wish/need to
return true;
#else
#ifdef digitalPinToTimer
#if defined(ARDUINO_ARCH_ESP32)
return (brakePin != UNUSED_PIN); // This was just (true) but we probably do need to check for UNUSED_PIN!
#elif defined(__arm__)
// On ARM we can use digitalPinHasPWM
return ((brakePin!=UNUSED_PIN) && (digitalPinHasPWM(brakePin)));
#elif defined(digitalPinToTimer)
return ((brakePin!=UNUSED_PIN) && (digitalPinToTimer(brakePin)));
#else
return (brakePin<14 && brakePin >1);
#endif //digitalPinToTimer
#endif //ESP32/ARM
#endif
}
inline int getRawCurrentTripValue() {
return rawCurrentTripValue;

View File

@@ -26,7 +26,8 @@
#include "MotorDriver.h"
#include "DCCTimer.h"
#include "DIAG.h"
#include"CommandDistributor.h"
#include "CommandDistributor.h"
#include "DCCEXParser.h"
// Virtualised Motor shield multi-track hardware Interface
#define FOR_EACH_TRACK(t) for (byte t=0;t<=lastTrack;t++)
@@ -154,10 +155,16 @@ void TrackManager::setDCCSignal( bool on) {
HAVE_PORTA(shadowPORTA=PORTA);
HAVE_PORTB(shadowPORTB=PORTB);
HAVE_PORTC(shadowPORTC=PORTC);
HAVE_PORTD(shadowPORTD=PORTD);
HAVE_PORTE(shadowPORTE=PORTE);
HAVE_PORTF(shadowPORTF=PORTF);
APPLY_BY_MODE(TRACK_MODE_MAIN,setSignal(on));
HAVE_PORTA(PORTA=shadowPORTA);
HAVE_PORTB(PORTB=shadowPORTB);
HAVE_PORTC(PORTC=shadowPORTC);
HAVE_PORTD(PORTD=shadowPORTD);
HAVE_PORTE(PORTE=shadowPORTE);
HAVE_PORTF(PORTF=shadowPORTF);
}
void TrackManager::setCutout( bool on) {
@@ -172,10 +179,16 @@ void TrackManager::setPROGSignal( bool on) {
HAVE_PORTA(shadowPORTA=PORTA);
HAVE_PORTB(shadowPORTB=PORTB);
HAVE_PORTC(shadowPORTC=PORTC);
HAVE_PORTD(shadowPORTD=PORTD);
HAVE_PORTE(shadowPORTE=PORTE);
HAVE_PORTF(shadowPORTF=PORTF);
APPLY_BY_MODE(TRACK_MODE_PROG,setSignal(on));
HAVE_PORTA(PORTA=shadowPORTA);
HAVE_PORTB(PORTB=shadowPORTB);
HAVE_PORTC(PORTC=shadowPORTC);
HAVE_PORTD(PORTD=shadowPORTD);
HAVE_PORTE(PORTE=shadowPORTE);
HAVE_PORTF(PORTF=shadowPORTF);
}
// setDCSignal(), called from normal context
@@ -319,6 +332,7 @@ bool TrackManager::parseJ(Print *stream, int16_t params, int16_t p[])
FOR_EACH_TRACK(t)
streamTrackState(stream,t);
return true;
}
p[0]-=HASH_KEYWORD_A; // convert A... to 0....
@@ -353,32 +367,36 @@ void TrackManager::streamTrackState(Print* stream, byte t) {
// null stream means send to commandDistributor for broadcast
if (track[t]==NULL) return;
auto format=F("");
bool pstate = TrackManager::isPowerOn(t);
switch(track[t]->getMode()) {
case TRACK_MODE_MAIN:
format=F("<= %c MAIN>\n");
if (pstate) {format=F("<= %c MAIN ON>\n");} else {format = F("<= %c MAIN OFF>\n");}
break;
#ifndef DISABLE_PROG
case TRACK_MODE_PROG:
format=F("<= %c PROG>\n");
if (pstate) {format=F("<= %c PROG ON>\n");} else {format=F("<= %c PROG OFF>\n");}
break;
#endif
case TRACK_MODE_NONE:
format=F("<= %c NONE>\n");
if (pstate) {format=F("<= %c NONE ON>\n");} else {format=F("<= %c NONE OFF>\n");}
break;
case TRACK_MODE_EXT:
format=F("<= %c EXT>\n");
if (pstate) {format=F("<= %c EXT ON>\n");} else {format=F("<= %c EXT OFF>\n");}
break;
case TRACK_MODE_DC:
format=F("<= %c DC %d>\n");
if (pstate) {format=F("<= %c DC %d ON>\n");} else {format=F("<= %c DC %d OFF>\n");}
break;
case TRACK_MODE_DCX:
format=F("<= %c DCX %d>\n");
if (pstate) {format=F("<= %c DCX %d ON>\n");} else {format=F("<= %c DCX %d OFF>\n");}
break;
default:
break; // unknown, dont care
}
if (stream) StringFormatter::send(stream,format,'A'+t,trackDCAddr[t]);
else CommandDistributor::broadcastTrackState(format,'A'+t,trackDCAddr[t]);
if (stream) StringFormatter::send(stream,format,'A'+t, trackDCAddr[t]);
else CommandDistributor::broadcastTrackState(format,'A'+t, trackDCAddr[t]);
}
byte TrackManager::nextCycleTrack=MAX_TRACKS;
@@ -412,49 +430,70 @@ std::vector<MotorDriver *>TrackManager::getMainDrivers() {
}
#endif
void TrackManager::setPower2(bool setProg,POWERMODE mode) {
void TrackManager::setPower2(bool setProg,bool setJoin, POWERMODE mode) {
if (!setProg) mainPowerGuess=mode;
FOR_EACH_TRACK(t) {
MotorDriver * driver=track[t];
if (!driver) continue;
switch (track[t]->getMode()) {
case TRACK_MODE_MAIN:
if (setProg) break;
// toggle brake before turning power on - resets overcurrent error
// on the Pololu board if brake is wired to ^D2.
// XXX see if we can make this conditional
driver->setBrake(true);
driver->setBrake(false); // DCC runs with brake off
driver->setPower(mode);
break;
case TRACK_MODE_DC:
case TRACK_MODE_DCX:
if (setProg) break;
driver->setBrake(true); // DC starts with brake on
applyDCSpeed(t); // speed match DCC throttles
driver->setPower(mode);
break;
case TRACK_MODE_PROG:
if (!setProg) break;
driver->setBrake(true);
driver->setBrake(false);
driver->setPower(mode);
break;
case TRACK_MODE_EXT:
driver->setBrake(true);
driver->setBrake(false);
driver->setPower(mode);
break;
case TRACK_MODE_NONE:
break;
}
TrackManager::setTrackPower(setProg, setJoin, mode, t);
}
return;
}
void TrackManager::setTrackPower(bool setProg, bool setJoin, POWERMODE mode, byte thistrack) {
//DIAG(F("SetTrackPower Processing Track %d"), thistrack);
MotorDriver * driver=track[thistrack];
if (!driver) return;
switch (track[thistrack]->getMode()) {
case TRACK_MODE_MAIN:
if (setProg) break;
// toggle brake before turning power on - resets overcurrent error
// on the Pololu board if brake is wired to ^D2.
// XXX see if we can make this conditional
driver->setBrake(true);
driver->setBrake(false); // DCC runs with brake off
driver->setPower(mode);
break;
case TRACK_MODE_DC:
case TRACK_MODE_DCX:
//DIAG(F("Processing track - %d setProg %d"), thistrack, setProg);
if (setProg || setJoin) break;
driver->setBrake(true); // DC starts with brake on
applyDCSpeed(thistrack); // speed match DCC throttles
driver->setPower(mode);
break;
case TRACK_MODE_PROG:
if (!setProg && !setJoin) break;
driver->setBrake(true);
driver->setBrake(false);
driver->setPower(mode);
break;
case TRACK_MODE_EXT:
driver->setBrake(true);
driver->setBrake(false);
driver->setPower(mode);
break;
case TRACK_MODE_NONE:
break;
}
}
void TrackManager::reportPowerChange(Print* stream, byte thistrack) {
// This function is for backward JMRI compatibility only
// It reports the first track only, as main, regardless of track settings.
// <c MeterName value C/V unit min max res warn>
int maxCurrent=track[0]->raw2mA(track[0]->getRawCurrentTripValue());
StringFormatter::send(stream, F("<c CurrentMAIN %d C Milli 0 %d 1 %d>\n"),
track[0]->raw2mA(track[0]->getCurrentRaw(false)), maxCurrent, maxCurrent);
}
POWERMODE TrackManager::getProgPower() {
FOR_EACH_TRACK(t)
if (track[t]->getMode()==TRACK_MODE_PROG)
return track[t]->getPower();
return track[t]->getPower();
return POWERMODE::OFF;
}
@@ -526,3 +565,32 @@ bool TrackManager::isPowerOn(byte t) {
return true;
}
bool TrackManager::isProg(byte t) {
if (track[t]->getMode()==TRACK_MODE_PROG)
return true;
return false;
}
byte TrackManager::returnMode(byte t) {
return (track[t]->getMode());
}
int16_t TrackManager::returnDCAddr(byte t) {
return (trackDCAddr[t]);
}
const char* TrackManager::getModeName(byte Mode) {
//DIAG(F("PowerMode %d"), Mode);
switch (Mode)
{
case 1: return "NONE";
case 2: return "MAIN";
case 4: return "PROG";
case 8: return "DC";
case 16: return "DCX";
case 32: return "EXT";
default: return "----";
}
}

View File

@@ -39,6 +39,10 @@ const byte TRACK_NUMBER_5=5, TRACK_NUMBER_F=5;
const byte TRACK_NUMBER_6=6, TRACK_NUMBER_G=6;
const byte TRACK_NUMBER_7=7, TRACK_NUMBER_H=7;
// These constants help EXRAIL macros convert Track Power e.g. SET_POWER(A ON|OFF).
const byte TRACK_POWER_0=0, TRACK_POWER_OFF=0;
const byte TRACK_POWER_1=1, TRACK_POWER_ON=1;
class TrackManager {
public:
static void Setup(const FSH * shieldName,
@@ -60,10 +64,14 @@ class TrackManager {
#ifdef ARDUINO_ARCH_ESP32
static std::vector<MotorDriver *>getMainDrivers();
#endif
static void setPower2(bool progTrack,POWERMODE mode);
static void setPower2(bool progTrack,bool joinTrack,POWERMODE mode);
static void setPower(POWERMODE mode) {setMainPower(mode); setProgPower(mode);}
static void setMainPower(POWERMODE mode) {setPower2(false,mode);}
static void setProgPower(POWERMODE mode) {setPower2(true,mode);}
static void setMainPower(POWERMODE mode) {setPower2(false,false,mode);}
static void setProgPower(POWERMODE mode) {setPower2(true,false,mode);}
static void setJoinPower(POWERMODE mode) {setPower2(false,true,mode);}
static void setTrackPower(bool setProg, bool setJoin, POWERMODE mode, byte thistrack);
static const int16_t MAX_TRACKS=8;
static bool setTrackMode(byte track, TRACK_MODE mode, int16_t DCaddr=0);
@@ -77,9 +85,14 @@ class TrackManager {
static void sampleCurrent();
static void reportGauges(Print* stream);
static void reportCurrent(Print* stream);
static void reportPowerChange(Print* stream, byte thistrack);
static void reportObsoleteCurrent(Print* stream);
static void streamTrackState(Print* stream, byte t);
static bool isPowerOn(byte t);
static bool isProg(byte t);
static byte returnMode(byte t);
static int16_t returnDCAddr(byte t);
static const char* getModeName(byte Mode);
static int16_t joinRelay;
static bool progTrackSyncMain; // true when prog track is a siding switched to main

View File

@@ -24,6 +24,7 @@
//#include "IO_TouchKeypad.h // Touch keypad with 16 keys
//#include "IO_EXTurntable.h" // Turntable-EX turntable controller
//#include "IO_EXFastClock.h" // FastClock driver
//#include "IO_PCA9555.h" // 16-bit I/O expander (NXP & Texas Instruments).
//==========================================================================
// The function halSetup() is invoked from CS if it exists within the build.

View File

@@ -3,7 +3,18 @@
#include "StringFormatter.h"
#define VERSION "5.1.9"
#define VERSION "5.1.12"
// 5.1.12 - Added Power commands <0 A> & <1 A> etc. and update to <=>
// Added EXRAIL SET_POWER(track, ON/OFF)
// Fixed a problem whereby <1 MAIN> also powered on PROG track
// Added functions to TrackManager.cpp to allow UserAddin code for power display on OLED/LCD
// Added - returnMode(byte t), returnDCAddr(byte t) & getModeName(byte Mode)
// 5.1.11 - STM32F4xx revised I2C clock setup, no correctly sets clock and has fully variable frequency selection
// 5.1.10 - STM32F4xx DCCEXanalogWrite to handle PWM generation for TrackManager DC/DCX
// - STM32F4xx DCC 58uS timer now using non-PWM output timers where possible
// - ESP32 brakeCanPWM check now detects UNUSED_PIN
// - ARM architecture brakeCanPWM now uses digitalPinHasPWM()
// - STM32F4xx shadowpin extensions to handle pins on ports D, E and F
// 5.1.9 - Fixed IO_PCA9555'h to work with PCA9548 mux, tested OK
// 5.1.8 - STM32Fxx ADCee extension to support ADCs #2 and #3
// 5.1.7 - Fix turntable broadcasts for non-movement activities and <JP> result