mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-11-22 23:56:13 +01:00
Merge branch 'devel' into devel-nmck
This commit is contained in:
commit
d8881deb6a
|
@ -29,6 +29,11 @@
|
|||
#include "DCCWaveform.h"
|
||||
#include "DCC.h"
|
||||
#include "TrackManager.h"
|
||||
#include "StringFormatter.h"
|
||||
|
||||
// variables to hold clock time
|
||||
int16_t lastclocktime;
|
||||
int8_t lastclockrate;
|
||||
|
||||
|
||||
#if WIFI_ON || ETHERNET_ON || defined(SERIAL1_COMMANDS) || defined(SERIAL2_COMMANDS) || defined(SERIAL3_COMMANDS)
|
||||
|
@ -155,6 +160,50 @@ void CommandDistributor::broadcastTurnout(int16_t id, bool isClosed ) {
|
|||
#endif
|
||||
}
|
||||
|
||||
void CommandDistributor::broadcastClockTime(int16_t time, int8_t rate) {
|
||||
// The JMRI clock command is of the form : PFT65871<;>4
|
||||
// The CS broadcast is of the form "<jC mmmm nn" where mmmm is time minutes and dd speed
|
||||
// The string below contains serial and Withrottle protocols which should
|
||||
// be safe for both types.
|
||||
broadcastReply(COMMAND_TYPE, F("<jC %d %d>\n"),time, rate);
|
||||
#ifdef CD_HANDLE_RING
|
||||
broadcastReply(WITHROTTLE_TYPE, F("PFT%d<;>%d\n"), time*60, rate);
|
||||
#endif
|
||||
}
|
||||
|
||||
void CommandDistributor::setClockTime(int16_t clocktime, int8_t clockrate, byte opt) {
|
||||
// opt - case 1 save the latest time if changed
|
||||
// case 2 broadcast the time when requested
|
||||
// case 3 display latest time
|
||||
switch (opt)
|
||||
{
|
||||
case 1:
|
||||
if (clocktime != lastclocktime){
|
||||
if (Diag::CMD) {
|
||||
DIAG(F("Clock Command Received"));
|
||||
DIAG(F("Received Clock Time is: %d at rate: %d"), clocktime, clockrate);
|
||||
}
|
||||
LCD(6,F("Clk Time:%d Sp %d"), clocktime, clockrate);
|
||||
// look for an event for this time
|
||||
RMFT2::clockEvent(clocktime,1);
|
||||
// Now tell everyone else what the time is.
|
||||
CommandDistributor::broadcastClockTime(clocktime, clockrate);
|
||||
lastclocktime = clocktime;
|
||||
lastclockrate = clockrate;
|
||||
}
|
||||
return;
|
||||
|
||||
case 2:
|
||||
CommandDistributor::broadcastClockTime(lastclocktime, lastclockrate);
|
||||
return;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
int16_t CommandDistributor::retClockTime() {
|
||||
return lastclocktime;
|
||||
}
|
||||
|
||||
void CommandDistributor::broadcastLoco(byte slot) {
|
||||
DCC::LOCO * sp=&DCC::speedTable[slot];
|
||||
broadcastReply(COMMAND_TYPE, F("<l %d %d %d %l>\n"), sp->loco,slot,sp->speedCode,sp->functions);
|
||||
|
|
|
@ -25,6 +25,7 @@
|
|||
#include "RingStream.h"
|
||||
#include "StringBuffer.h"
|
||||
#include "defines.h"
|
||||
#include "EXRAIL2.h"
|
||||
|
||||
#if WIFI_ON | ETHERNET_ON
|
||||
// Command Distributor must handle a RingStream of clients
|
||||
|
@ -45,10 +46,14 @@ public :
|
|||
static void broadcastLoco(byte slot);
|
||||
static void broadcastSensor(int16_t id, bool value);
|
||||
static void broadcastTurnout(int16_t id, bool isClosed);
|
||||
static void broadcastClockTime(int16_t time, int8_t rate);
|
||||
static void setClockTime(int16_t time, int8_t rate, byte opt);
|
||||
static int16_t retClockTime();
|
||||
static void broadcastPower();
|
||||
static void broadcastText(const FSH * msg);
|
||||
template<typename... Targs> static void broadcastReply(clientType type, Targs... msg);
|
||||
static void forget(byte clientId);
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
|
|
|
@ -99,6 +99,9 @@ void setup()
|
|||
// Initialise HAL layer before reading EEprom or setting up MotorDrivers
|
||||
IODevice::begin();
|
||||
|
||||
// As the setup of a motor shield may require a read of the current sense input from the ADC,
|
||||
// let's make sure to initialise the ADCee class!
|
||||
ADCee::begin();
|
||||
// Responsibility 3: Start the DCC engine.
|
||||
// Note: this provides DCC with two motor drivers, main and prog, which handle the motor shield(s)
|
||||
// Standard supported devices have pre-configured macros but custome hardware installations require
|
||||
|
|
|
@ -510,6 +510,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
|
|||
|
||||
case 's': // <s>
|
||||
StringFormatter::send(stream, F("<iDCC-EX V-%S / %S / %S G-%S>\n"), F(VERSION), F(ARDUINO_TYPE), DCC::getMotorShieldName(), F(GITHUB_SHA));
|
||||
CommandDistributor::broadcastPower(); // <s> is the only "get power status" command we have
|
||||
Turnout::printAll(stream); //send all Turnout states
|
||||
Output::printAll(stream); //send all Output states
|
||||
Sensor::printAll(stream); //send all Sensor states
|
||||
|
@ -570,9 +571,19 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
|
|||
|
||||
case 'J' : // throttle info access
|
||||
{
|
||||
if ((params<1) | (params>2)) break; // <J>
|
||||
if ((params<1) | (params>3)) break; // <J>
|
||||
//if ((params<1) | (params>2)) break; // <J>
|
||||
int16_t id=(params==2)?p[1]:0;
|
||||
switch(p[0]) {
|
||||
case HASH_KEYWORD_C: // <JC mmmm nn> sets time and speed
|
||||
if (params==1) { // <JC> returns latest time
|
||||
int16_t x = CommandDistributor::retClockTime();
|
||||
StringFormatter::send(stream, F("<jC %d>\n"), x);
|
||||
return;
|
||||
}
|
||||
CommandDistributor::setClockTime(p[1], p[2], 1);
|
||||
return;
|
||||
|
||||
case HASH_KEYWORD_A: // <JA> returns automations/routes
|
||||
StringFormatter::send(stream, F("<jA"));
|
||||
if (params==1) {// <JA>
|
||||
|
@ -616,14 +627,17 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
|
|||
else { // <JT id>
|
||||
Turnout * t=Turnout::get(id);
|
||||
if (!t || t->isHidden()) StringFormatter::send(stream, F(" %d X"),id);
|
||||
else StringFormatter::send(stream, F(" %d %c \"%S\""),
|
||||
id,t->isThrown()?'T':'C',
|
||||
else {
|
||||
const FSH *tdesc = NULL;
|
||||
#ifdef EXRAIL_ACTIVE
|
||||
RMFT2::getTurnoutDescription(id)
|
||||
#else
|
||||
F("")
|
||||
#endif
|
||||
);
|
||||
tdesc = RMFT2::getTurnoutDescription(id);
|
||||
#endif
|
||||
if (tdesc == NULL)
|
||||
tdesc = F("");
|
||||
StringFormatter::send(stream, F(" %d %c \"%S\""),
|
||||
id,t->isThrown()?'T':'C',
|
||||
tdesc);
|
||||
}
|
||||
}
|
||||
StringFormatter::send(stream, F(">\n"));
|
||||
return;
|
||||
|
|
14
DCCTimer.h
14
DCCTimer.h
|
@ -1,5 +1,5 @@
|
|||
/*
|
||||
* © 2022 Paul M. Antoine
|
||||
* © 2022-2023 Paul M. Antoine
|
||||
* © 2021 Mike S
|
||||
* © 2021-2022 Harald Barth
|
||||
* © 2021 Fred Decker
|
||||
|
@ -102,9 +102,14 @@ private:
|
|||
// that an offset can be initialized.
|
||||
class ADCee {
|
||||
public:
|
||||
// init does add the pin to the list of scanned pins (if this
|
||||
// begin is called for any setup that must be done before
|
||||
// **init** can be called. On some architectures this involves ADC
|
||||
// initialisation and clock routing, sampling times etc.
|
||||
static void begin();
|
||||
// init adds the pin to the list of scanned pins (if this
|
||||
// platform's implementation scans pins) and returns the first
|
||||
// read value. It is called before the regular scan is started.
|
||||
// read value (which is why it required begin to have been called first!)
|
||||
// It must be called before the regular scan is started.
|
||||
static int init(uint8_t pin);
|
||||
// read does read the pin value from the scanned cache or directly
|
||||
// if this is a platform that does not scan. fromISR is a hint if
|
||||
|
@ -117,9 +122,6 @@ private:
|
|||
// On platforms that scan, it is called from waveform ISR
|
||||
// only on a regular basis.
|
||||
static void scan();
|
||||
// begin is called for any setup that must be done before
|
||||
// scan can be called.
|
||||
static void begin();
|
||||
// bit array of used pins (max 16)
|
||||
static uint16_t usedpins;
|
||||
// cached analog values (malloc:ed to actual number of ADC channels)
|
||||
|
|
|
@ -168,23 +168,6 @@ int ADCee::init(uint8_t pin) {
|
|||
if (id > NUM_ADC_INPUTS)
|
||||
return -1023;
|
||||
|
||||
// Dummy read using Arduino library
|
||||
analogReadResolution(12);
|
||||
value = analogRead(pin);
|
||||
|
||||
// Reconfigure ADC
|
||||
ADC->CTRLA.bit.ENABLE = 0; // disable ADC
|
||||
while( ADC->STATUS.bit.SYNCBUSY == 1 ); // wait for synchronization
|
||||
|
||||
ADC->CTRLB.reg &= 0b1111100011001111; // mask PRESCALER and RESSEL bits
|
||||
ADC->CTRLB.reg |= ADC_CTRLB_PRESCALER_DIV64 | // divide Clock by 16
|
||||
ADC_CTRLB_RESSEL_12BIT; // Result 12 bits, 10 bits possible
|
||||
ADC->AVGCTRL.reg = ADC_AVGCTRL_SAMPLENUM_1 | // take 1 sample at a time
|
||||
ADC_AVGCTRL_ADJRES(0x00ul); // adjusting result by 0
|
||||
ADC->SAMPCTRL.reg = 0x00ul; // sampling Time Length = 0
|
||||
ADC->CTRLA.bit.ENABLE = 1; // enable ADC
|
||||
while( ADC->STATUS.bit.SYNCBUSY == 1 ); // wait for synchronization
|
||||
|
||||
// Permanently configure SAMD IO MUX for that pin
|
||||
pinPeripheral(pin, PIO_ANALOG);
|
||||
ADC->INPUTCTRL.bit.MUXPOS = g_APinDescription[pin].ulADCChannelNumber; // Selection for the positive ADC input
|
||||
|
@ -205,9 +188,11 @@ int ADCee::init(uint8_t pin) {
|
|||
|
||||
return value;
|
||||
}
|
||||
|
||||
int16_t ADCee::ADCmax() {
|
||||
return 4095;
|
||||
}
|
||||
|
||||
/*
|
||||
* Read function ADCee::read(pin) to get value instead of analogRead(pin)
|
||||
*/
|
||||
|
|
|
@ -39,7 +39,7 @@ HardwareSerial Serial1(PB7, PA15); // Rx=PB7, Tx=PA15 -- CN7 pins 17 and 21 - F
|
|||
HardwareSerial Serial6(PA12, PA11); // Rx=PA12, Tx=PA11 -- CN10 pins 12 and 14 - F411RE
|
||||
#elif defined(ARDUINO_NUCLEO_F446RE)
|
||||
// Nucleo-64 boards don't have Serial1 defined by default
|
||||
HardwareSerial Serial1(PA10, PB6); // Rx=PA10, Tx=PB6 -- CN10 pins 17 and 33 - F446RE
|
||||
HardwareSerial Serial1(PA10, PB6); // Rx=PA10, Tx=PB6 -- CN10 pins 33 and 17 - F446RE
|
||||
// Serial2 is defined to use USART2 by default, but is in fact used as the diag console
|
||||
// via the debugger on the Nucleo-64. It is therefore unavailable for other DCC-EX uses like WiFi, DFPlayer, etc.
|
||||
#elif defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)
|
||||
|
@ -96,7 +96,7 @@ void DCCTimer::clearPWM() {
|
|||
void DCCTimer::getSimulatedMacAddress(byte mac[6]) {
|
||||
volatile uint32_t *serno1 = (volatile uint32_t *)0x1FFF7A10;
|
||||
volatile uint32_t *serno2 = (volatile uint32_t *)0x1FFF7A14;
|
||||
volatile uint32_t *serno3 = (volatile uint32_t *)0x1FFF7A18;
|
||||
// volatile uint32_t *serno3 = (volatile uint32_t *)0x1FFF7A18;
|
||||
|
||||
volatile uint32_t m1 = *serno1;
|
||||
volatile uint32_t m2 = *serno2;
|
||||
|
@ -131,31 +131,148 @@ void DCCTimer::reset() {
|
|||
while(true) {};
|
||||
}
|
||||
|
||||
#define NUM_ADC_INPUTS NUM_ANALOG_INPUTS
|
||||
|
||||
// TODO: may need to use uint32_t on STMF4xx variants with > 16 analog inputs!
|
||||
uint16_t ADCee::usedpins = 0;
|
||||
int * ADCee::analogvals = NULL;
|
||||
uint32_t * analogchans = NULL;
|
||||
bool adc1configured = false;
|
||||
|
||||
int16_t ADCee::ADCmax() {
|
||||
return 4095;
|
||||
}
|
||||
|
||||
int ADCee::init(uint8_t pin) {
|
||||
return analogRead(pin);
|
||||
uint id = pin - A0;
|
||||
int value = 0;
|
||||
PinName stmpin = digitalPin[analogInputPin[id]];
|
||||
uint32_t stmgpio = stmpin / 16; // 16-bits per GPIO port group on STM32
|
||||
uint32_t adcchan = STM_PIN_CHANNEL(pinmap_function(stmpin, PinMap_ADC)); // find ADC channel (only valid for ADC1!)
|
||||
GPIO_TypeDef * gpioBase;
|
||||
|
||||
// Port config - find which port we're on and power it up
|
||||
switch(stmgpio) {
|
||||
case 0x00:
|
||||
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; //Power up PORTA
|
||||
gpioBase = GPIOA;
|
||||
break;
|
||||
case 0x01:
|
||||
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN; //Power up PORTB
|
||||
gpioBase = GPIOB;
|
||||
break;
|
||||
case 0x02:
|
||||
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN; //Power up PORTC
|
||||
gpioBase = GPIOC;
|
||||
break;
|
||||
}
|
||||
|
||||
// Set pin mux mode to analog input
|
||||
gpioBase->MODER |= (0b011 << (stmpin << 1)); // Set pin mux to analog mode
|
||||
|
||||
// Set the sampling rate for that analog input
|
||||
if (adcchan < 10)
|
||||
ADC1->SMPR2 |= (0b111 << (adcchan * 3)); // Channel sampling rate 480 cycles
|
||||
else
|
||||
ADC1->SMPR1 |= (0b111 << ((adcchan - 10) * 3)); // Channel sampling rate 480 cycles
|
||||
|
||||
// Read the inital ADC value for this analog input
|
||||
ADC1->SQR3 = adcchan; // 1st conversion in regular sequence
|
||||
ADC1->CR2 |= (1 << 30); // Start 1st conversion SWSTART
|
||||
while(!(ADC1->SR & (1 << 1))); // Wait until conversion is complete
|
||||
value = ADC1->DR; // Read value from register
|
||||
|
||||
if (analogvals == NULL)
|
||||
{
|
||||
analogvals = (int *)calloc(NUM_ADC_INPUTS+1, sizeof(int));
|
||||
analogchans = (uint32_t *)calloc(NUM_ADC_INPUTS+1, sizeof(uint32_t));
|
||||
}
|
||||
analogvals[id] = value; // Store sampled value
|
||||
analogchans[id] = adcchan; // Keep track of which ADC channel is used for reading this pin
|
||||
usedpins |= (1 << id); // This pin is now ready
|
||||
|
||||
return value;
|
||||
}
|
||||
|
||||
/*
|
||||
* Read function ADCee::read(pin) to get value instead of analogRead(pin)
|
||||
*/
|
||||
int ADCee::read(uint8_t pin, bool fromISR) {
|
||||
int current;
|
||||
if (!fromISR) noInterrupts();
|
||||
current = analogRead(pin);
|
||||
if (!fromISR) interrupts();
|
||||
return current;
|
||||
uint8_t id = pin - A0;
|
||||
// Was this pin initialised yet?
|
||||
if ((usedpins & (1<<id) ) == 0)
|
||||
return -1023;
|
||||
// We do not need to check (analogvals == NULL)
|
||||
// because usedpins would still be 0 in that case
|
||||
return analogvals[id];
|
||||
}
|
||||
|
||||
/*
|
||||
* Scan function that is called from interrupt
|
||||
*/
|
||||
#pragma GCC push_options
|
||||
#pragma GCC optimize ("-O3")
|
||||
void ADCee::scan() {
|
||||
static uint id = 0; // id and mask are the same thing but it is faster to
|
||||
static uint16_t mask = 1; // increment and shift instead to calculate mask from id
|
||||
static bool waiting = false;
|
||||
|
||||
if (waiting) {
|
||||
// look if we have a result
|
||||
if (!(ADC1->SR & (1 << 1)))
|
||||
return; // no result, continue to wait
|
||||
// found value
|
||||
analogvals[id] = ADC1->DR;
|
||||
// advance at least one track
|
||||
// for scope debug TrackManager::track[1]->setBrake(0);
|
||||
waiting = false;
|
||||
id++;
|
||||
mask = mask << 1;
|
||||
if (id == NUM_ADC_INPUTS+1) {
|
||||
id = 0;
|
||||
mask = 1;
|
||||
}
|
||||
}
|
||||
if (!waiting) {
|
||||
if (usedpins == 0) // otherwise we would loop forever
|
||||
return;
|
||||
// look for a valid track to sample or until we are around
|
||||
while (true) {
|
||||
if (mask & usedpins) {
|
||||
// start new ADC aquire on id
|
||||
ADC1->SQR3 = analogchans[id]; //1st conversion in regular sequence
|
||||
ADC1->CR2 |= (1 << 30); //Start 1st conversion SWSTART
|
||||
// for scope debug TrackManager::track[1]->setBrake(1);
|
||||
waiting = true;
|
||||
return;
|
||||
}
|
||||
id++;
|
||||
mask = mask << 1;
|
||||
if (id == NUM_ADC_INPUTS+1) {
|
||||
id = 0;
|
||||
mask = 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
#pragma GCC pop_options
|
||||
|
||||
void ADCee::begin() {
|
||||
noInterrupts();
|
||||
//ADC1 config sequence
|
||||
// TODO: currently defaults to ADC1, may need more to handle other members of STM32F4xx family
|
||||
RCC->APB2ENR |= (1 << 8); //Enable ADC1 clock (Bit8)
|
||||
// Set ADC prescaler - DIV8 ~ 40ms, DIV6 ~ 30ms, DIV4 ~ 20ms, DIV2 ~ 11ms
|
||||
ADC->CCR = (0 << 16); // Set prescaler 0=DIV2, 1=DIV4, 2=DIV6, 3=DIV8
|
||||
ADC1->CR1 &= ~(1 << 8); //SCAN mode disabled (Bit8)
|
||||
ADC1->CR1 &= ~(3 << 24); //12bit resolution (Bit24,25 0b00)
|
||||
ADC1->SQR1 = (1 << 20); //Set number of conversions projected (L[3:0] 0b0001) -> 1 conversion
|
||||
ADC1->CR2 &= ~(1 << 1); //Single conversion
|
||||
ADC1->CR2 &= ~(1 << 11); //Right alignment of data bits bit12....bit0
|
||||
ADC1->SQR1 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register
|
||||
ADC1->SQR2 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register
|
||||
ADC1->SQR3 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register
|
||||
ADC1->CR2 |= (1 << 0); // Switch on ADC1
|
||||
interrupts();
|
||||
}
|
||||
#endif
|
|
@ -62,7 +62,6 @@ const bool signalTransform[]={
|
|||
/* WAVE_PENDING (should not happen) -> */ LOW};
|
||||
|
||||
void DCCWaveform::begin() {
|
||||
ADCee::begin();
|
||||
DCCTimer::begin(DCCWaveform::interruptHandler);
|
||||
}
|
||||
|
||||
|
|
40
EXRAIL2.cpp
40
EXRAIL2.cpp
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* © 2021 Neil McKechnie
|
||||
* © 2021-2022 Harald Barth
|
||||
* © 2021-2023 Harald Barth
|
||||
* © 2020-2022 Chris Harlow
|
||||
* All rights reserved.
|
||||
*
|
||||
|
@ -92,6 +92,7 @@ LookList * RMFT2::onRedLookup=NULL;
|
|||
LookList * RMFT2::onAmberLookup=NULL;
|
||||
LookList * RMFT2::onGreenLookup=NULL;
|
||||
LookList * RMFT2::onChangeLookup=NULL;
|
||||
LookList * RMFT2::onClockLookup=NULL;
|
||||
|
||||
#define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter)
|
||||
#define SKIPOP progCounter+=3
|
||||
|
@ -175,6 +176,8 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
|
|||
onAmberLookup=LookListLoader(OPCODE_ONAMBER);
|
||||
onGreenLookup=LookListLoader(OPCODE_ONGREEN);
|
||||
onChangeLookup=LookListLoader(OPCODE_ONCHANGE);
|
||||
onClockLookup=LookListLoader(OPCODE_ONTIME);
|
||||
|
||||
|
||||
// Second pass startup, define any turnouts or servos, set signals red
|
||||
// add sequences onRoutines to the lookups
|
||||
|
@ -744,6 +747,10 @@ void RMFT2::loop2() {
|
|||
skipIf=IODevice::readAnalogue(operand)>=(int)(getOperand(1));
|
||||
break;
|
||||
|
||||
case OPCODE_IFLOCO: // do if the loco is the active one
|
||||
skipIf=loco!=(uint16_t)operand; // bad luck if someone enters negative loco numbers into EXRAIL
|
||||
break;
|
||||
|
||||
case OPCODE_IFNOT: // do next operand if sensor not set
|
||||
skipIf=readSensor(operand);
|
||||
break;
|
||||
|
@ -975,6 +982,7 @@ void RMFT2::loop2() {
|
|||
case OPCODE_ONAMBER:
|
||||
case OPCODE_ONGREEN:
|
||||
case OPCODE_ONCHANGE:
|
||||
case OPCODE_ONTIME:
|
||||
|
||||
break;
|
||||
|
||||
|
@ -1076,11 +1084,23 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
|
|||
|
||||
// Manage invert (HIGH on) pins
|
||||
bool aHigh=sigid & ACTIVE_HIGH_SIGNAL_FLAG;
|
||||
|
||||
|
||||
// set the three pins
|
||||
if (redpin) IODevice::write(redpin,(rag==SIGNAL_RED || rag==SIMAMBER)^aHigh);
|
||||
if (amberpin) IODevice::write(amberpin,(rag==SIGNAL_AMBER)^aHigh);
|
||||
if (greenpin) IODevice::write(greenpin,(rag==SIGNAL_GREEN || rag==SIMAMBER)^aHigh);
|
||||
if (redpin) {
|
||||
bool redval=(rag==SIGNAL_RED || rag==SIMAMBER);
|
||||
if (!aHigh) redval=!redval;
|
||||
IODevice::write(redpin,redval);
|
||||
}
|
||||
if (amberpin) {
|
||||
bool amberval=(rag==SIGNAL_AMBER);
|
||||
if (!aHigh) amberval=!amberval;
|
||||
IODevice::write(amberpin,amberval);
|
||||
}
|
||||
if (greenpin) {
|
||||
bool greenval=(rag==SIGNAL_GREEN || rag==SIMAMBER);
|
||||
if (!aHigh) greenval=!greenval;
|
||||
IODevice::write(greenpin,greenval);
|
||||
}
|
||||
}
|
||||
|
||||
/* static */ bool RMFT2::isSignal(int16_t id,char rag) {
|
||||
|
@ -1106,7 +1126,14 @@ void RMFT2::changeEvent(int16_t vpin, bool change) {
|
|||
// Hunt for an ONCHANGE for this sensor
|
||||
if (change) handleEvent(F("CHANGE"),onChangeLookup,vpin);
|
||||
}
|
||||
|
||||
|
||||
void RMFT2::clockEvent(int16_t clocktime, bool change) {
|
||||
// Hunt for an ONTIME for this time
|
||||
if (Diag::CMD)
|
||||
DIAG(F("Looking for clock event at : %d"), clocktime);
|
||||
if (change) handleEvent(F("CLOCK"),onClockLookup,clocktime);
|
||||
}
|
||||
|
||||
void RMFT2::handleEvent(const FSH* reason,LookList* handlers, int16_t id) {
|
||||
int pc= handlers->find(id);
|
||||
if (pc<0) return;
|
||||
|
@ -1221,4 +1248,3 @@ void RMFT2::thrungeString(uint32_t strfar, thrunger mode, byte id) {
|
|||
default: break;
|
||||
}
|
||||
}
|
||||
|
|
@ -1,6 +1,7 @@
|
|||
/*
|
||||
* © 2021 Neil McKechnie
|
||||
* © 2020-2022 Chris Harlow
|
||||
* © 2023 Harald Barth
|
||||
* All rights reserved.
|
||||
*
|
||||
* This file is part of CommandStation-EX
|
||||
|
@ -55,6 +56,8 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,
|
|||
OPCODE_SET_TRACK,
|
||||
OPCODE_ONRED,OPCODE_ONAMBER,OPCODE_ONGREEN,
|
||||
OPCODE_ONCHANGE,
|
||||
OPCODE_ONCLOCKTIME,
|
||||
OPCODE_ONTIME,
|
||||
|
||||
// OPcodes below this point are skip-nesting IF operations
|
||||
// placed here so that they may be skipped as a group
|
||||
|
@ -67,6 +70,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,
|
|||
OPCODE_IFRANDOM,OPCODE_IFRESERVE,
|
||||
OPCODE_IFCLOSED,OPCODE_IFTHROWN,
|
||||
OPCODE_IFRE,
|
||||
OPCODE_IFLOCO
|
||||
};
|
||||
|
||||
enum thrunger: byte {
|
||||
|
@ -116,6 +120,7 @@ class LookList {
|
|||
static void turnoutEvent(int16_t id, bool closed);
|
||||
static void activateEvent(int16_t addr, bool active);
|
||||
static void changeEvent(int16_t id, bool change);
|
||||
static void clockEvent(int16_t clocktime, bool change);
|
||||
static const int16_t SERVO_SIGNAL_FLAG=0x4000;
|
||||
static const int16_t ACTIVE_HIGH_SIGNAL_FLAG=0x2000;
|
||||
static const int16_t DCC_SIGNAL_FLAG=0x1000;
|
||||
|
@ -173,6 +178,7 @@ private:
|
|||
static LookList * onAmberLookup;
|
||||
static LookList * onGreenLookup;
|
||||
static LookList * onChangeLookup;
|
||||
static LookList * onClockLookup;
|
||||
|
||||
// Local variables - exist for each instance/task
|
||||
RMFT2 *next; // loop chain
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/*
|
||||
* © 2021-2022 Chris Harlow
|
||||
* © 2020,2021 Chris Harlow. All rights reserved.
|
||||
* © 2020-2022 Chris Harlow. All rights reserved.
|
||||
* © 2023 Harald Barth
|
||||
*
|
||||
* This file is part of CommandStation-EX
|
||||
*
|
||||
|
@ -66,6 +66,7 @@
|
|||
#undef IFCLOSED
|
||||
#undef IFGREEN
|
||||
#undef IFGTE
|
||||
#undef IFLOCO
|
||||
#undef IFLT
|
||||
#undef IFNOT
|
||||
#undef IFRANDOM
|
||||
|
@ -87,6 +88,8 @@
|
|||
#undef ONDEACTIVATE
|
||||
#undef ONDEACTIVATEL
|
||||
#undef ONCLOSE
|
||||
#undef ONTIME
|
||||
#undef ONCLOCKTIME
|
||||
#undef ONGREEN
|
||||
#undef ONRED
|
||||
#undef ONTHROW
|
||||
|
@ -182,6 +185,7 @@
|
|||
#define IFCLOSED(turnout_id)
|
||||
#define IFGREEN(signal_id)
|
||||
#define IFGTE(sensor_id,value)
|
||||
#define IFLOCO(loco_id)
|
||||
#define IFLT(sensor_id,value)
|
||||
#define IFNOT(sensor_id)
|
||||
#define IFRANDOM(percent)
|
||||
|
@ -200,6 +204,8 @@
|
|||
#define ONACTIVATE(addr,subaddr)
|
||||
#define ONACTIVATEL(linear)
|
||||
#define ONAMBER(signal_id)
|
||||
#define ONTIME(value)
|
||||
#define ONCLOCKTIME(hours,mins)
|
||||
#define ONDEACTIVATE(addr,subaddr)
|
||||
#define ONDEACTIVATEL(linear)
|
||||
#define ONCLOSE(turnout_id)
|
||||
|
|
|
@ -1,6 +1,7 @@
|
|||
/*
|
||||
* © 2021 Neil McKechnie
|
||||
* © 2020-2022 Chris Harlow
|
||||
* © 2023 Harald Barth
|
||||
* All rights reserved.
|
||||
*
|
||||
* This file is part of CommandStation-EX
|
||||
|
@ -55,6 +56,10 @@
|
|||
// helper macro for turnout description as HIDDEN
|
||||
#define HIDDEN "\x01"
|
||||
|
||||
// helper macro to strip leading zeros off time inputs
|
||||
// (10#mins)%100)
|
||||
#define STRIP_ZERO(value) 10##value%100
|
||||
|
||||
// Pass 1 Implements aliases
|
||||
#include "EXRAIL2MacroReset.h"
|
||||
#undef ALIAS
|
||||
|
@ -279,6 +284,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = {
|
|||
#define IFCLOSED(turnout_id) OPCODE_IFCLOSED,V(turnout_id),
|
||||
#define IFGREEN(signal_id) OPCODE_IFGREEN,V(signal_id),
|
||||
#define IFGTE(sensor_id,value) OPCODE_IFGTE,V(sensor_id),OPCODE_PAD,V(value),
|
||||
#define IFLOCO(loco_id) OPCODE_IFLOCO,V(loco_id),
|
||||
#define IFLT(sensor_id,value) OPCODE_IFLT,V(sensor_id),OPCODE_PAD,V(value),
|
||||
#define IFNOT(sensor_id) OPCODE_IFNOT,V(sensor_id),
|
||||
#define IFRANDOM(percent) OPCODE_IFRANDOM,V(percent),
|
||||
|
@ -298,6 +304,8 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = {
|
|||
#define ONACTIVATEL(linear) OPCODE_ONACTIVATE,V(linear+3),
|
||||
#define ONAMBER(signal_id) OPCODE_ONAMBER,V(signal_id),
|
||||
#define ONCLOSE(turnout_id) OPCODE_ONCLOSE,V(turnout_id),
|
||||
#define ONTIME(value) OPCODE_ONTIME,V(value),
|
||||
#define ONCLOCKTIME(hours,mins) OPCODE_ONTIME,V((STRIP_ZERO(hours)*60)+STRIP_ZERO(mins)),
|
||||
#define ONDEACTIVATE(addr,subaddr) OPCODE_ONDEACTIVATE,V(addr<<2|subaddr),
|
||||
#define ONDEACTIVATEL(linear) OPCODE_ONDEACTIVATE,V(linear+3),
|
||||
#define ONGREEN(signal_id) OPCODE_ONGREEN,V(signal_id),
|
||||
|
|
|
@ -1 +1 @@
|
|||
#define GITHUB_SHA "devel-202212051450Z"
|
||||
#define GITHUB_SHA "devel-202301290750Z"
|
||||
|
|
128
IO_EXFastclock.h
Normal file
128
IO_EXFastclock.h
Normal file
|
@ -0,0 +1,128 @@
|
|||
/*
|
||||
* © 2022, Colin Murdoch. All rights reserved.
|
||||
*
|
||||
* This file is part of CommandStation-EX
|
||||
*
|
||||
* This is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* It is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
/*
|
||||
* The IO_EXFastclock device driver is used to interface the standalone fast clock and receive time data.
|
||||
*
|
||||
* The EX-fastClock code lives in a separate repo (https://github.com/DCC-EX/EX-Fastclock) and contains the clock logic.
|
||||
*
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef IO_EXFastclock_h
|
||||
#define IO_EXFastclock_h
|
||||
|
||||
|
||||
#include "IODevice.h"
|
||||
#include "I2CManager.h"
|
||||
#include "DIAG.h"
|
||||
#include "EXRAIL2.h"
|
||||
#include "CommandDistributor.h"
|
||||
|
||||
bool FAST_CLOCK_EXISTS = true;
|
||||
|
||||
class EXFastClock : public IODevice {
|
||||
public:
|
||||
// Constructor
|
||||
EXFastClock(uint8_t I2CAddress){
|
||||
_I2CAddress = I2CAddress;
|
||||
addDevice(this);
|
||||
}
|
||||
|
||||
static void create(uint8_t _I2CAddress) {
|
||||
|
||||
DIAG(F("Checking for Clock"));
|
||||
// Start by assuming we will find the clock
|
||||
// Check if specified I2C address is responding (blocking operation)
|
||||
// Returns I2C_STATUS_OK (0) if OK, or error code.
|
||||
uint8_t _checkforclock = I2CManager.checkAddress(_I2CAddress);
|
||||
DIAG(F("Clock check result - %d"), _checkforclock);
|
||||
// XXXX change thistosave2 bytes
|
||||
if (_checkforclock == 0) {
|
||||
FAST_CLOCK_EXISTS = true;
|
||||
//DIAG(F("I2C Fast Clock found at x%x"), _I2CAddress);
|
||||
new EXFastClock(_I2CAddress);
|
||||
}
|
||||
else {
|
||||
FAST_CLOCK_EXISTS = false;
|
||||
//DIAG(F("No Fast Clock found"));
|
||||
LCD(6,F("CLOCK NOT FOUND"));
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
private:
|
||||
uint8_t _I2CAddress;
|
||||
|
||||
|
||||
// Initialisation of Fastclock
|
||||
void _begin() override {
|
||||
|
||||
if (FAST_CLOCK_EXISTS == true) {
|
||||
I2CManager.begin();
|
||||
if (I2CManager.exists(_I2CAddress)) {
|
||||
_deviceState = DEVSTATE_NORMAL;
|
||||
#ifdef DIAG_IO
|
||||
_display();
|
||||
#endif
|
||||
} else {
|
||||
_deviceState = DEVSTATE_FAILED;
|
||||
//LCD(6,F("CLOCK NOT FOUND"));
|
||||
DIAG(F("Fast Clock Not Found at address %d"), _I2CAddress);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Processing loop to obtain clock time
|
||||
|
||||
void _loop(unsigned long currentMicros) override{
|
||||
|
||||
if (FAST_CLOCK_EXISTS==true) {
|
||||
uint8_t readBuffer[3];
|
||||
byte a,b;
|
||||
#ifdef EXRAIL_ACTIVE
|
||||
I2CManager.read(_I2CAddress, readBuffer, 3);
|
||||
// XXXX change this to save a few bytes
|
||||
a = readBuffer[0];
|
||||
b = readBuffer[1];
|
||||
//_clocktime = (a << 8) + b;
|
||||
//_clockrate = readBuffer[2];
|
||||
|
||||
CommandDistributor::setClockTime(((a << 8) + b), readBuffer[2], 1);
|
||||
//setClockTime(int16_t clocktime, int8_t clockrate, byte opt);
|
||||
|
||||
// As the minimum clock increment is 2 seconds delay a bit - say 1 sec.
|
||||
// Clock interval is 60/ clockspeed i.e 60/b seconds
|
||||
delayUntil(currentMicros + ((60/b) * 1000000));
|
||||
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
|
||||
// Display EX-FastClock device driver info.
|
||||
void _display() {
|
||||
DIAG(F("FastCLock on I2C:x%x - %S"), _I2CAddress, (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F(""));
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif
|
|
@ -66,6 +66,10 @@ private:
|
|||
_i2cAddress = i2cAddress;
|
||||
_numDigitalPins = numDigitalPins;
|
||||
_numAnaloguePins = numAnaloguePins;
|
||||
_digitalPinBytes = (numDigitalPins+7)/8;
|
||||
_analoguePinBytes = numAnaloguePins * 2;
|
||||
_digitalInputStates=(byte*) calloc(_digitalPinBytes,1);
|
||||
_analogueInputStates=(byte*) calloc(_analoguePinBytes,1);
|
||||
addDevice(this);
|
||||
}
|
||||
|
||||
|
@ -77,16 +81,16 @@ private:
|
|||
_digitalOutBuffer[1] = _numDigitalPins;
|
||||
_digitalOutBuffer[2] = _numAnaloguePins;
|
||||
// Send config, if EXIORDY returned, we're good, otherwise go offline
|
||||
I2CManager.read(_i2cAddress, _digitalInBuffer, 1, _digitalOutBuffer, 3);
|
||||
if (_digitalInBuffer[0] != EXIORDY) {
|
||||
I2CManager.read(_i2cAddress, _commandBuffer, 1, _digitalOutBuffer, 3);
|
||||
if (_commandBuffer[0] != EXIORDY) {
|
||||
DIAG(F("ERROR configuring EX-IOExpander device, I2C:x%x"), (int)_i2cAddress);
|
||||
_deviceState = DEVSTATE_FAILED;
|
||||
return;
|
||||
}
|
||||
// Attempt to get version, if we don't get it, we don't care, don't go offline
|
||||
// Using digital in buffer in reverse to save RAM
|
||||
_digitalInBuffer[0] = EXIOVER;
|
||||
I2CManager.read(_i2cAddress, _versionBuffer, 3, _digitalInBuffer, 1);
|
||||
_commandBuffer[0] = EXIOVER;
|
||||
I2CManager.read(_i2cAddress, _versionBuffer, 3, _commandBuffer, 1);
|
||||
_majorVer = _versionBuffer[0];
|
||||
_minorVer = _versionBuffer[1];
|
||||
_patchVer = _versionBuffer[2];
|
||||
|
@ -121,27 +125,37 @@ private:
|
|||
int _configureAnalogIn(VPIN vpin) override {
|
||||
if (vpin < _firstVpin + _numDigitalPins) {
|
||||
DIAG(F("EX-IOExpander ERROR: Vpin %d is a digital pin, cannot use as an analogue pin"), vpin);
|
||||
return false;
|
||||
}
|
||||
return false;
|
||||
int pin = vpin - _firstVpin;
|
||||
_analogueOutBuffer[0] = EXIOENAN;
|
||||
_analogueOutBuffer[1] = pin;
|
||||
I2CManager.write(_i2cAddress, _analogueOutBuffer, 2);
|
||||
return true;
|
||||
}
|
||||
|
||||
void _loop(unsigned long currentMicros) override {
|
||||
(void)currentMicros; // remove warning
|
||||
_commandBuffer[0] = EXIORDD;
|
||||
I2CManager.read(_i2cAddress, _digitalInputStates, _digitalPinBytes, _commandBuffer, 1);
|
||||
_commandBuffer[0] = EXIORDAN;
|
||||
I2CManager.read(_i2cAddress, _analogueInputStates, _analoguePinBytes, _commandBuffer, 1);
|
||||
}
|
||||
|
||||
int _readAnalogue(VPIN vpin) override {
|
||||
if (vpin < _firstVpin + _numDigitalPins) return false;
|
||||
int pin = vpin - _firstVpin;
|
||||
_analogueOutBuffer[0] = EXIORDAN;
|
||||
_analogueOutBuffer[1] = pin;
|
||||
I2CManager.read(_i2cAddress, _analogueInBuffer, 2, _analogueOutBuffer, 2);
|
||||
return (_analogueInBuffer[1] << 8) + _analogueInBuffer[0];
|
||||
int pin = vpin - _firstVpin - _numDigitalPins;
|
||||
uint8_t _pinLSBByte = pin * 2;
|
||||
uint8_t _pinMSBByte = _pinLSBByte + 1;
|
||||
return (_analogueInputStates[_pinMSBByte] << 8) + _analogueInputStates[_pinLSBByte];
|
||||
}
|
||||
|
||||
int _read(VPIN vpin) override {
|
||||
if (vpin >= _firstVpin + _numDigitalPins) return false;
|
||||
int pin = vpin - _firstVpin;
|
||||
_digitalOutBuffer[0] = EXIORDD;
|
||||
_digitalOutBuffer[1] = pin;
|
||||
_digitalOutBuffer[2] = 0x00; // Don't need to use this for reading
|
||||
I2CManager.read(_i2cAddress, _digitalInBuffer, 1, _digitalOutBuffer, 3);
|
||||
return _digitalInBuffer[0];
|
||||
uint8_t pinByte = pin / 8;
|
||||
bool value = _digitalInputStates[pinByte] >> (pin - pinByte * 8);
|
||||
return value;
|
||||
}
|
||||
|
||||
void _write(VPIN vpin, int value) override {
|
||||
|
@ -172,16 +186,17 @@ private:
|
|||
uint8_t _i2cAddress;
|
||||
uint8_t _numDigitalPins;
|
||||
uint8_t _numAnaloguePins;
|
||||
int _digitalPinBytes;
|
||||
int _analoguePinBytes;
|
||||
byte _analogueInBuffer[2];
|
||||
byte _analogueOutBuffer[2];
|
||||
byte _digitalOutBuffer[3];
|
||||
byte _digitalInBuffer[1];
|
||||
uint8_t _versionBuffer[3];
|
||||
uint8_t _majorVer = 0;
|
||||
uint8_t _minorVer = 0;
|
||||
uint8_t _patchVer = 0;
|
||||
byte* _digitalInputStates;
|
||||
byte* _analogueInputStates;
|
||||
uint8_t _digitalPinBytes = 0;
|
||||
uint8_t _analoguePinBytes = 0;
|
||||
byte _commandBuffer[1];
|
||||
|
||||
enum {
|
||||
EXIOINIT = 0xE0, // Flag to initialise setup procedure
|
||||
|
@ -191,7 +206,8 @@ private:
|
|||
EXIORDAN = 0xE4, // Flag to read an analogue input
|
||||
EXIOWRD = 0xE5, // Flag for digital write
|
||||
EXIORDD = 0xE6, // Flag to read digital input
|
||||
EXIOENAN = 0xE7, // Flag eo enable an analogue pin
|
||||
};
|
||||
};
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
|
|
@ -525,7 +525,7 @@ void WiThrottle::sendTurnouts(Print* stream) {
|
|||
}
|
||||
void WiThrottle::sendRoster(Print* stream) {
|
||||
rosterSent=true;
|
||||
#ifdef EXRAIL_ACTIVE
|
||||
#ifdef EXRAIL_ACTIVE
|
||||
StringFormatter::send(stream,F("RL%d"), RMFT2::rosterNameCount);
|
||||
for (int16_t r=0;r<RMFT2::rosterNameCount;r++) {
|
||||
int16_t cabid=GETHIGHFLASHW(RMFT2::rosterIdList,r*2);
|
||||
|
@ -533,11 +533,13 @@ void WiThrottle::sendRoster(Print* stream) {
|
|||
RMFT2::getRosterName(cabid),cabid,cabid<128?'S':'L');
|
||||
}
|
||||
StringFormatter::send(stream,F("\n"));
|
||||
#else
|
||||
(void)stream; // remove warning
|
||||
#endif
|
||||
}
|
||||
void WiThrottle::sendRoutes(Print* stream) {
|
||||
routesSent=true;
|
||||
#ifdef EXRAIL_ACTIVE
|
||||
#ifdef EXRAIL_ACTIVE
|
||||
StringFormatter::send(stream,F("PRT]\\[Routes}|{Route]\\[Set}|{2]\\[Handoff}|{4\nPRL"));
|
||||
// first pass automations
|
||||
for (int ix=0;;ix+=2) {
|
||||
|
@ -554,7 +556,8 @@ void WiThrottle::sendRoutes(Print* stream) {
|
|||
StringFormatter::send(stream,F("]\\[R%d}|{%S}|{2"),id,desc);
|
||||
}
|
||||
StringFormatter::send(stream,F("\n"));
|
||||
|
||||
#else
|
||||
(void)stream; // remove warning
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -609,4 +612,4 @@ void WiThrottle::sendFunctions(Print* stream, byte loco) {
|
|||
int fstate=DCC::getFn(locoid,fKey);
|
||||
if (fstate>=0) StringFormatter::send(stream,F("M%cA%c%d<;>F%d%d\n"),myLocos[loco].throttle,LorS(locoid),locoid,fstate,fKey);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -224,4 +224,8 @@ The configuration file for DCC-EX Command Station
|
|||
//
|
||||
//#define SERIAL_BT_COMMANDS
|
||||
|
||||
|
||||
// FastClock Enabler
|
||||
// To build the FastClock code into the CS please uncomment the line below
|
||||
//#define USEFASTCLOCK
|
||||
/////////////////////////////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include "IO_VL53L0X.h" // Laser time-of-flight sensor
|
||||
#include "IO_DFPlayer.h" // MP3 sound player
|
||||
//#include "IO_EXTurntable.h" // Turntable-EX turntable controller
|
||||
|
||||
//#include "IO_EXFastClock.h" // FastClock driver
|
||||
|
||||
//==========================================================================
|
||||
// The function halSetup() is invoked from CS if it exists within the build.
|
||||
|
@ -221,6 +221,19 @@ void halSetup() {
|
|||
//RotaryEncoder::create(700, 1, 0x70);
|
||||
//RotaryEncoder::create(701, 2, 0x71);
|
||||
|
||||
//=======================================================================
|
||||
// The following directive defines an EX-FastClock instance.
|
||||
//=======================================================================
|
||||
// EXFastCLock::create(I2C Address)
|
||||
//
|
||||
// The parameters are:
|
||||
//
|
||||
// I2C address=0x55 (decimal 85)
|
||||
//
|
||||
// Note that the I2C address is defined in the EX-FastClock code, and 0x55 is the default.
|
||||
|
||||
|
||||
// EXFastClock::create(0x55);
|
||||
|
||||
}
|
||||
|
||||
|
|
|
@ -4,7 +4,13 @@
|
|||
#include "StringFormatter.h"
|
||||
|
||||
|
||||
#define VERSION "4.2.9pre1"
|
||||
#define VERSION "4.2.14"
|
||||
// 4.2.14 STM32F4xx fast ADC read implementation
|
||||
// 4.2.13 Broadcast power for <s> again
|
||||
// 4.2.12 Bugfix for issue #299 TurnoutDescription NULL
|
||||
// 4.2.11 Exrail IFLOCO feature added
|
||||
// 4.2.10 SIGNAL/SIGNALH bug fix as they were inverted
|
||||
// IO_EXIOExpander.h input speed optimisation
|
||||
// 4.2.9 duinoNodes support
|
||||
// 4.2.8 HIGHMEM (EXRAIL support beyond 64kb)
|
||||
// Withrottle connect/disconnect improvements
|
||||
|
|
Loading…
Reference in New Issue
Block a user