mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2025-07-29 10:23:45 +02:00
Compare commits
16 Commits
v4.2.44-De
...
devel-AT2
Author | SHA1 | Date | |
---|---|---|---|
|
0fdaf789ab | ||
|
ea15d38240 | ||
|
a3c9800aba | ||
|
28d9843133 | ||
|
33306219c8 | ||
|
d857c4f2e4 | ||
|
70fae16ab3 | ||
|
f465020e93 | ||
|
235bcc9ff0 | ||
|
d2cc60812d | ||
|
75f274e3b7 | ||
|
ff53b90034 | ||
|
1daa0a9ba9 | ||
|
294b9693c5 | ||
|
16e44eb11a | ||
|
31ecba08d8 |
@@ -2,6 +2,7 @@
|
||||
* © 2022 Harald Barth
|
||||
* © 2020-2021 Chris Harlow
|
||||
* © 2020 Gregor Baues
|
||||
* © 2022 Colin Murdoch
|
||||
* All rights reserved.
|
||||
*
|
||||
* This file is part of CommandStation-EX
|
||||
@@ -227,11 +228,8 @@ void CommandDistributor::broadcastPower() {
|
||||
LCD(2,F("Power %S%S"),state=='1'?F("On"):F("Off"),reason);
|
||||
}
|
||||
|
||||
void CommandDistributor::broadcastText(const FSH * msg) {
|
||||
broadcastReply(COMMAND_TYPE, F("<I %S>\n"),msg);
|
||||
#ifdef CD_HANDLE_RING
|
||||
broadcastReply(WITHROTTLE_TYPE, F("Hm%S\n"), msg);
|
||||
#endif
|
||||
void CommandDistributor::broadcastRaw(clientType type, char * msg) {
|
||||
broadcastReply(type, F("%s"),msg);
|
||||
}
|
||||
|
||||
void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr) {
|
||||
|
@@ -2,6 +2,8 @@
|
||||
* © 2022 Harald Barth
|
||||
* © 2020-2021 Chris Harlow
|
||||
* © 2020 Gregor Baues
|
||||
* © 2022 Colin Murdoch
|
||||
*
|
||||
* All rights reserved.
|
||||
*
|
||||
* This file is part of CommandStation-EX
|
||||
@@ -33,8 +35,9 @@
|
||||
#endif
|
||||
|
||||
class CommandDistributor {
|
||||
private:
|
||||
public:
|
||||
enum clientType: byte {NONE_TYPE,COMMAND_TYPE,WITHROTTLE_TYPE};
|
||||
private:
|
||||
static void broadcastToClients(clientType type);
|
||||
static StringBuffer * broadcastBufferWriter;
|
||||
#ifdef CD_HANDLE_RING
|
||||
@@ -50,7 +53,7 @@ public :
|
||||
static void setClockTime(int16_t time, int8_t rate, byte opt);
|
||||
static int16_t retClockTime();
|
||||
static void broadcastPower();
|
||||
static void broadcastText(const FSH * msg);
|
||||
static void broadcastRaw(clientType type,char * msg);
|
||||
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);
|
||||
|
@@ -7,6 +7,7 @@
|
||||
* © 2020-2021 M Steve Todd
|
||||
* © 2020-2021 Fred Decker
|
||||
* © 2020-2021 Chris Harlow
|
||||
* © 2022 Colin Murdoch
|
||||
* All rights reserved.
|
||||
*
|
||||
* This file is part of CommandStation-EX
|
||||
|
@@ -1,7 +1,7 @@
|
||||
/*
|
||||
* © 2022 Paul M. Antoine
|
||||
* © 2022-2023 Paul M. Antoine
|
||||
* © 2021 Mike S
|
||||
* © 2021-2022 Harald Barth
|
||||
* © 2021-2023 Harald Barth
|
||||
* © 2021 Fred Decker
|
||||
* All rights reserved.
|
||||
*
|
||||
@@ -62,6 +62,9 @@ class DCCTimer {
|
||||
static bool isPWMPin(byte pin);
|
||||
static void setPWM(byte pin, bool high);
|
||||
static void clearPWM();
|
||||
static void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency);
|
||||
static void DCCEXanalogWrite(uint8_t pin, int value);
|
||||
|
||||
// Update low ram level. Allow for extra bytes to be specified
|
||||
// by estimation or inspection, that may be used by other
|
||||
// called subroutines. Must be called with interrupts disabled.
|
||||
|
@@ -150,6 +150,45 @@ int DCCTimer::freeMemory() {
|
||||
void DCCTimer::reset() {
|
||||
ESP.restart();
|
||||
}
|
||||
|
||||
#include "esp32-hal.h"
|
||||
#include "soc/soc_caps.h"
|
||||
|
||||
|
||||
#ifdef SOC_LEDC_SUPPORT_HS_MODE
|
||||
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM<<1)
|
||||
#else
|
||||
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM)
|
||||
#endif
|
||||
|
||||
static int8_t pin_to_channel[SOC_GPIO_PIN_COUNT] = { 0 };
|
||||
static int cnt_channel = LEDC_CHANNELS;
|
||||
|
||||
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency) {
|
||||
if (pin < SOC_GPIO_PIN_COUNT) {
|
||||
if (pin_to_channel[pin] != 0) {
|
||||
ledcSetup(pin_to_channel[pin], frequency, 8);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
|
||||
if (pin < SOC_GPIO_PIN_COUNT) {
|
||||
if (pin_to_channel[pin] == 0) {
|
||||
if (!cnt_channel) {
|
||||
log_e("No more PWM channels available! All %u already used", LEDC_CHANNELS);
|
||||
return;
|
||||
}
|
||||
pin_to_channel[pin] = --cnt_channel;
|
||||
ledcAttachPin(pin, cnt_channel);
|
||||
ledcSetup(cnt_channel, 1000, 8);
|
||||
} else {
|
||||
ledcAttachPin(pin, pin_to_channel[pin]);
|
||||
}
|
||||
ledcWrite(pin_to_channel[pin], value);
|
||||
}
|
||||
}
|
||||
|
||||
int ADCee::init(uint8_t pin) {
|
||||
pinMode(pin, ANALOG);
|
||||
adc1_config_width(ADC_WIDTH_BIT_12);
|
||||
|
@@ -1,8 +1,8 @@
|
||||
/*
|
||||
* © 2023 Neil McKechnie
|
||||
* © 2022 Paul M. Antoine
|
||||
* © 2022-23 Paul M. Antoine
|
||||
* © 2021 Mike S
|
||||
* © 2021 Harald Barth
|
||||
* © 2021, 2023 Harald Barth
|
||||
* © 2021 Fred Decker
|
||||
* © 2021 Chris Harlow
|
||||
* © 2021 David Cutting
|
||||
@@ -43,11 +43,18 @@ HardwareSerial Serial6(PA12, PA11); // Rx=PA12, Tx=PA11 -- CN10 pins 12 and 14
|
||||
HardwareSerial Serial1(PA10, PB6); // Rx=PA10 (D2), Tx=PB6 (D10) -- CN10 pins 17 and 9 - 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.
|
||||
// NB: USART3 and USART6 are available but as yet undefined
|
||||
#elif defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)
|
||||
// Nucleo-144 boards don't have Serial1 defined by default
|
||||
HardwareSerial Serial1(PG9, PG14); // Rx=PG9, Tx=PG14 -- D0, D1 - F412ZG/F446ZE
|
||||
// Serial2 is defined to use USART2 by default, but is in fact used as the diag console
|
||||
// via the debugger on the Nucleo-144. It is therefore unavailable for other DCC-EX uses like WiFi, DFPlayer, etc.
|
||||
// NB:
|
||||
// On all of the above, USART3, and USART6 are available but as yet undefined
|
||||
// On F446ZE and F429ZI, UART4, UART5 are also available but as yet undefined
|
||||
// On F429ZI, UART7 and UART8 are also available but as yet undefined
|
||||
#else
|
||||
#warning Serial1 not defined
|
||||
#error STM32 board selected is not yet explicitly supported - so Serial1 peripheral is not defined
|
||||
#endif
|
||||
|
||||
///////////////////////////////////////////////////////////////////////////////////////////////
|
||||
@@ -227,6 +234,9 @@ void DCCTimer::reset() {
|
||||
#define NUM_ADC_INPUTS NUM_ANALOG_INPUTS
|
||||
|
||||
// TODO: may need to use uint32_t on STMF4xx variants with > 16 analog inputs!
|
||||
#if defined(ARDUINO_NUCLEO_F446RE) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)
|
||||
#warning STM32 board selected not fully supported - only use ADC1 inputs 0-15 for current sensing!
|
||||
#endif
|
||||
uint16_t ADCee::usedpins = 0;
|
||||
int * ADCee::analogvals = NULL;
|
||||
uint32_t * analogchans = NULL;
|
||||
@@ -286,13 +296,15 @@ int ADCee::init(uint8_t pin) {
|
||||
while(!(ADC1->SR & (1 << 1))); // Wait until conversion is complete
|
||||
value = ADC1->DR; // Read value from register
|
||||
|
||||
if (analogvals == NULL)
|
||||
{
|
||||
uint8_t id = pin - PNUM_ANALOG_BASE;
|
||||
if (id > 15) { // today we have not enough bits in the mask to support more
|
||||
return -1021;
|
||||
}
|
||||
|
||||
if (analogvals == NULL) { // allocate analogvals and analogchans if this is the first invocation of init.
|
||||
analogvals = (int *)calloc(NUM_ADC_INPUTS+1, sizeof(int));
|
||||
analogchans = (uint32_t *)calloc(NUM_ADC_INPUTS+1, sizeof(uint32_t));
|
||||
}
|
||||
|
||||
uint8_t id = pin - PNUM_ANALOG_BASE;
|
||||
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
|
||||
|
@@ -1,61 +0,0 @@
|
||||
/*
|
||||
* © 2022 Harald Barth
|
||||
* 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/>.
|
||||
*/
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
#include <Arduino.h>
|
||||
#include "ESP32-fixes.h"
|
||||
|
||||
#include "esp32-hal.h"
|
||||
#include "soc/soc_caps.h"
|
||||
|
||||
|
||||
#ifdef SOC_LEDC_SUPPORT_HS_MODE
|
||||
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM<<1)
|
||||
#else
|
||||
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM)
|
||||
#endif
|
||||
|
||||
static int8_t pin_to_channel[SOC_GPIO_PIN_COUNT] = { 0 };
|
||||
static int cnt_channel = LEDC_CHANNELS;
|
||||
|
||||
void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency) {
|
||||
if (pin < SOC_GPIO_PIN_COUNT) {
|
||||
if (pin_to_channel[pin] != 0) {
|
||||
ledcSetup(pin_to_channel[pin], frequency, 8);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void DCCEXanalogWrite(uint8_t pin, int value) {
|
||||
if (pin < SOC_GPIO_PIN_COUNT) {
|
||||
if (pin_to_channel[pin] == 0) {
|
||||
if (!cnt_channel) {
|
||||
log_e("No more PWM channels available! All %u already used", LEDC_CHANNELS);
|
||||
return;
|
||||
}
|
||||
pin_to_channel[pin] = --cnt_channel;
|
||||
ledcAttachPin(pin, cnt_channel);
|
||||
ledcSetup(cnt_channel, 1000, 8);
|
||||
} else {
|
||||
ledcAttachPin(pin, pin_to_channel[pin]);
|
||||
}
|
||||
ledcWrite(pin_to_channel[pin], value);
|
||||
}
|
||||
}
|
||||
#endif
|
@@ -1,26 +0,0 @@
|
||||
/*
|
||||
* © 2022 Harald Barth
|
||||
* 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/>.
|
||||
*/
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
#pragma once
|
||||
#include <Arduino.h>
|
||||
void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency);
|
||||
void DCCEXanalogWrite(uint8_t pin, int value);
|
||||
#endif
|
||||
|
18
EXRAIL2.cpp
18
EXRAIL2.cpp
@@ -2,6 +2,7 @@
|
||||
* © 2021 Neil McKechnie
|
||||
* © 2021-2023 Harald Barth
|
||||
* © 2020-2023 Chris Harlow
|
||||
* © 2022 Colin Murdoch
|
||||
* All rights reserved.
|
||||
*
|
||||
* This file is part of CommandStation-EX
|
||||
@@ -265,16 +266,17 @@ void RMFT2::setTurnoutHiddenState(Turnout * t) {
|
||||
char RMFT2::getRouteType(int16_t id) {
|
||||
for (int16_t i=0;;i+=2) {
|
||||
int16_t rid= GETHIGHFLASHW(routeIdList,i);
|
||||
if (rid==id) return 'R';
|
||||
if (rid==0) break;
|
||||
if (rid==id) return 'R';
|
||||
}
|
||||
for (int16_t i=0;;i+=2) {
|
||||
int16_t rid= GETHIGHFLASHW(automationIdList,i);
|
||||
if (rid==id) return 'A';
|
||||
if (rid==0) break;
|
||||
if (rid==id) return 'A';
|
||||
}
|
||||
return 'X';
|
||||
}
|
||||
}
|
||||
|
||||
// This filter intercepts <> commands to do the following:
|
||||
// - Implement RMFT specific commands/diagnostics
|
||||
// - Reject/modify JMRI commands that would interfere with RMFT processing
|
||||
@@ -1129,7 +1131,10 @@ 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);
|
||||
if (change) {
|
||||
handleEvent(F("CLOCK"),onClockLookup,clocktime);
|
||||
handleEvent(F("CLOCK"),onClockLookup,25*60+clocktime%60);
|
||||
}
|
||||
}
|
||||
|
||||
void RMFT2::handleEvent(const FSH* reason,LookList* handlers, int16_t id) {
|
||||
@@ -1237,7 +1242,10 @@ void RMFT2::thrungeString(uint32_t strfar, thrunger mode, byte id) {
|
||||
DCCEXParser::parseOne(&USB_SERIAL,(byte*)buffer->getString(),NULL);
|
||||
break;
|
||||
case thrunge_broadcast:
|
||||
// TODO CommandDistributor::broadcastText(buffer->getString());
|
||||
CommandDistributor::broadcastRaw(CommandDistributor::COMMAND_TYPE,buffer->getString());
|
||||
break;
|
||||
case thrunge_withrottle:
|
||||
CommandDistributor::broadcastRaw(CommandDistributor::WITHROTTLE_TYPE,buffer->getString());
|
||||
break;
|
||||
case thrunge_lcd:
|
||||
LCD(id,F("%s"),buffer->getString());
|
||||
|
@@ -1,6 +1,7 @@
|
||||
/*
|
||||
* © 2021 Neil McKechnie
|
||||
* © 2020-2022 Chris Harlow
|
||||
* © 2022 Colin Murdoch
|
||||
* © 2023 Harald Barth
|
||||
* All rights reserved.
|
||||
*
|
||||
@@ -76,7 +77,8 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,
|
||||
// Ensure thrunge_lcd is put last as there may be more than one display,
|
||||
// sequentially numbered from thrunge_lcd.
|
||||
enum thrunger: byte {
|
||||
thrunge_print, thrunge_broadcast, thrunge_serial,thrunge_parse,
|
||||
thrunge_print, thrunge_broadcast, thrunge_withrottle,
|
||||
thrunge_serial,thrunge_parse,
|
||||
thrunge_serial1, thrunge_serial2, thrunge_serial3,
|
||||
thrunge_serial4, thrunge_serial5, thrunge_serial6,
|
||||
thrunge_lcn,
|
||||
|
@@ -1,5 +1,6 @@
|
||||
/*
|
||||
* © 2020-2022 Chris Harlow. All rights reserved.
|
||||
* © 2022 Colin Murdoch
|
||||
* © 2023 Harald Barth
|
||||
*
|
||||
* This file is part of CommandStation-EX
|
||||
@@ -91,6 +92,7 @@
|
||||
#undef ONCLOSE
|
||||
#undef ONTIME
|
||||
#undef ONCLOCKTIME
|
||||
#undef ONCLOCKMINS
|
||||
#undef ONGREEN
|
||||
#undef ONRED
|
||||
#undef ONTHROW
|
||||
@@ -140,6 +142,7 @@
|
||||
#undef VIRTUAL_SIGNAL
|
||||
#undef VIRTUAL_TURNOUT
|
||||
#undef WAITFOR
|
||||
#undef WITHROTTLE
|
||||
#undef XFOFF
|
||||
#undef XFON
|
||||
|
||||
@@ -209,6 +212,7 @@
|
||||
#define ONAMBER(signal_id)
|
||||
#define ONTIME(value)
|
||||
#define ONCLOCKTIME(hours,mins)
|
||||
#define ONCLOCKMINS(mins)
|
||||
#define ONDEACTIVATE(addr,subaddr)
|
||||
#define ONDEACTIVATEL(linear)
|
||||
#define ONCLOSE(turnout_id)
|
||||
@@ -261,6 +265,7 @@
|
||||
#define VIRTUAL_SIGNAL(id)
|
||||
#define VIRTUAL_TURNOUT(id,description...)
|
||||
#define WAITFOR(pin)
|
||||
#define WITHROTTLE(msg)
|
||||
#define XFOFF(cab,func)
|
||||
#define XFON(cab,func)
|
||||
#endif
|
||||
|
@@ -1,6 +1,7 @@
|
||||
/*
|
||||
* © 2021 Neil McKechnie
|
||||
* © 2020-2022 Chris Harlow
|
||||
* © 2022 Colin Murdoch
|
||||
* © 2023 Harald Barth
|
||||
* All rights reserved.
|
||||
*
|
||||
@@ -152,6 +153,8 @@ const int StringMacroTracker1=__COUNTER__;
|
||||
lcdid=id;\
|
||||
break;\
|
||||
}
|
||||
#undef WITHROTTLE
|
||||
#define WITHROTTLE(msg) THRUNGE(msg,thrunge_withrottle)
|
||||
|
||||
void RMFT2::printMessage(uint16_t id) {
|
||||
thrunger tmode;
|
||||
@@ -316,6 +319,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = {
|
||||
#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 ONCLOCKMINS(mins) ONCLOCKTIME(25,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),
|
||||
@@ -366,6 +370,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = {
|
||||
#define UNLATCH(sensor_id) OPCODE_UNLATCH,V(sensor_id),
|
||||
#define VIRTUAL_SIGNAL(id)
|
||||
#define VIRTUAL_TURNOUT(id,description...) OPCODE_PINTURNOUT,V(id),OPCODE_PAD,V(0),
|
||||
#define WITHROTTLE(msg) PRINT(msg)
|
||||
#define WAITFOR(pin) OPCODE_WAITFOR,V(pin),
|
||||
#define XFOFF(cab,func) OPCODE_XFOFF,V(cab),OPCODE_PAD,V(func),
|
||||
#define XFON(cab,func) OPCODE_XFON,V(cab),OPCODE_PAD,V(func),
|
||||
|
@@ -1 +1 @@
|
||||
#define GITHUB_SHA "devel-202304092344Z"
|
||||
#define GITHUB_SHA "devel-202305022048Z"
|
||||
|
@@ -1,8 +1,8 @@
|
||||
/*
|
||||
* © 2022 Paul M Antoine
|
||||
* © 2022-2023 Paul M Antoine
|
||||
* © 2021 Mike S
|
||||
* © 2021 Fred Decker
|
||||
* © 2020-2022 Harald Barth
|
||||
* © 2020-2023 Harald Barth
|
||||
* © 2020-2021 Chris Harlow
|
||||
* All rights reserved.
|
||||
*
|
||||
@@ -27,10 +27,6 @@
|
||||
#include "DCCTimer.h"
|
||||
#include "DIAG.h"
|
||||
|
||||
#if defined(ARDUINO_ARCH_ESP32)
|
||||
#include "ESP32-fixes.h"
|
||||
#endif
|
||||
|
||||
bool MotorDriver::commonFaultPin=false;
|
||||
|
||||
volatile portreg_t shadowPORTA;
|
||||
@@ -38,7 +34,7 @@ volatile portreg_t shadowPORTB;
|
||||
volatile portreg_t shadowPORTC;
|
||||
|
||||
MotorDriver::MotorDriver(int16_t 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, int8_t fault_pin) {
|
||||
powerPin=power_pin;
|
||||
invertPower=power_pin < 0;
|
||||
if (invertPower) {
|
||||
@@ -112,6 +108,9 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
|
||||
|
||||
faultPin=fault_pin;
|
||||
if (faultPin != UNUSED_PIN) {
|
||||
invertFault=fault_pin < 0;
|
||||
faultPin=invertFault ? 0-fault_pin : fault_pin;
|
||||
DIAG(F("Fault pin = %d invert %d"), faultPin, invertFault);
|
||||
getFastPin(F("FAULT"),faultPin, 1 /*input*/, fastFaultPin);
|
||||
pinMode(faultPin, INPUT);
|
||||
}
|
||||
@@ -215,8 +214,12 @@ int MotorDriver::getCurrentRaw(bool fromISR) {
|
||||
// if (fromISR == false) DIAG(F("%c: %d"), trackLetter, current);
|
||||
current = current-senseOffset; // adjust with offset
|
||||
if (current<0) current=0-current;
|
||||
if ((faultPin != UNUSED_PIN) && isLOW(fastFaultPin) && powerMode==POWERMODE::ON)
|
||||
if ((faultPin != UNUSED_PIN) && powerMode==POWERMODE::ON) {
|
||||
if (invertFault && isLOW(fastFaultPin))
|
||||
return (current == 0 ? -1 : -current);
|
||||
if (!invertFault && !isLOW(fastFaultPin))
|
||||
return (current == 0 ? -1 : -current);
|
||||
}
|
||||
return current;
|
||||
|
||||
}
|
||||
@@ -286,7 +289,7 @@ void MotorDriver::setDCSignal(byte speedcode) {
|
||||
f = taurustones[ (tSpeed-2)/2 ] ;
|
||||
}
|
||||
}
|
||||
DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup
|
||||
DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup
|
||||
}
|
||||
#endif
|
||||
if (tSpeed <= 1) brake = 255;
|
||||
@@ -295,7 +298,7 @@ void MotorDriver::setDCSignal(byte speedcode) {
|
||||
if (invertBrake)
|
||||
brake=255-brake;
|
||||
#if defined(ARDUINO_ARCH_ESP32)
|
||||
DCCEXanalogWrite(brakePin,brake);
|
||||
DCCTimer::DCCEXanalogWrite(brakePin,brake);
|
||||
#else
|
||||
analogWrite(brakePin,brake);
|
||||
#endif
|
||||
|
@@ -112,7 +112,7 @@ class MotorDriver {
|
||||
public:
|
||||
|
||||
MotorDriver(int16_t 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, int8_t fault_pin);
|
||||
void setPower( POWERMODE mode);
|
||||
POWERMODE getPower() { return powerMode;}
|
||||
// as the port registers can be shadowed to get syncronized DCC signals
|
||||
@@ -202,6 +202,7 @@ class MotorDriver {
|
||||
bool dualSignal; // true to use signalPin2
|
||||
bool invertBrake; // brake pin passed as negative means pin is inverted
|
||||
bool invertPower; // power pin passed as negative means pin is inverted
|
||||
bool invertFault; // fault pin passed as negative means pin is inverted
|
||||
|
||||
// Raw to milliamp conversion factors avoiding float data types.
|
||||
// Milliamps=rawADCreading * sensefactorInternal / senseScale
|
||||
|
@@ -76,9 +76,13 @@
|
||||
// analog inputs. Here we use analog inputs A2 and A3 as A0 and A1 are wired in a way so that
|
||||
// they are not useable at the same time as WiFi (what a bummer). The numbers below are the
|
||||
// actual GPIO numbers. In comments the numbers the pins have on an Uno.
|
||||
#define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"), \
|
||||
new MotorDriver(25/* 3*/, 19/*12*/, UNUSED_PIN, 13/*9*/, 35/*A2*/, 0.70, 1500, UNUSED_PIN), \
|
||||
new MotorDriver(23/*11*/, 18/*13*/, UNUSED_PIN, 12/*8*/, 34/*A3*/, 0.70, 1500, UNUSED_PIN)
|
||||
#define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"), \
|
||||
new MotorDriver(25/* 3*/, 19/*12*/, UNUSED_PIN, 13/*9*/, 35/*A2*/, 0.70, 1500, UNUSED_PIN), \
|
||||
new MotorDriver(23/*11*/, 18/*13*/, UNUSED_PIN, 12/*8*/, 34/*A3*/, 0.70, 1500, UNUSED_PIN)
|
||||
|
||||
#define EX8874_SHIELD F("EX8874"),\
|
||||
new MotorDriver(25/* 3*/, 19/*12*/, UNUSED_PIN, 13/*9*/, 35/*A2*/, 1.17, 5000, -36 /*-A4*/), \
|
||||
new MotorDriver(23/*11*/, 18/*13*/, UNUSED_PIN, 12/*8*/, 34/*A3*/, 1.17, 5000, -39 /*-A5*/)
|
||||
|
||||
#else
|
||||
// STANDARD shield on any Arduino Uno or Mega compatible with the original specification.
|
||||
@@ -116,6 +120,10 @@
|
||||
new MotorDriver(2, 7, UNUSED_PIN, -9, A0, 10, 2500, 6), \
|
||||
new MotorDriver(4, 8, UNUSED_PIN, -10, A1, 10, 2500, 12)
|
||||
|
||||
#define EX8874_SHIELD F("EX8874"), \
|
||||
new MotorDriver( 3, 12, UNUSED_PIN, 9, A0, 4.86, 5000, -A4), \
|
||||
new MotorDriver(11, 13, UNUSED_PIN, 8, A1, 4.86, 5000, -A5)
|
||||
|
||||
// Firebox Mk1
|
||||
#define FIREBOX_MK1 F("FIREBOX_MK1"), \
|
||||
new MotorDriver(3, 6, 7, UNUSED_PIN, A5, 9.766, 5500, UNUSED_PIN), \
|
||||
|
@@ -149,6 +149,7 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password,
|
||||
const FSH* hostname, int port, byte channel) {
|
||||
bool ipOK = false;
|
||||
bool oldCmd = false;
|
||||
bool use_CUR = false;
|
||||
|
||||
char macAddress[17]; // mac address extraction
|
||||
|
||||
@@ -174,14 +175,21 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password,
|
||||
#ifdef DONT_TOUCH_WIFI_CONF
|
||||
DIAG(F("DONT_TOUCH_WIFI_CONF was set: Using existing config"));
|
||||
#else
|
||||
// Older ES versions have AT+CWJAP, newer ones have AT+CWJAP_CUR and AT+CWHOSTNAME
|
||||
StringFormatter::send(wifiStream, F("AT+CWJAP_CUR?\r\n"));
|
||||
// test for 2.x version firmware
|
||||
StringFormatter::send(wifiStream, F("AT+SYSSTORE=0\r\n"));
|
||||
if (!(checkForOK(2000, true))) {
|
||||
oldCmd=true;
|
||||
use_CUR=true;
|
||||
while (wifiStream->available()) StringFormatter::printEscape( wifiStream->read()); /// THIS IS A DIAG IN DISGUISE
|
||||
// Older ES versions have AT+CWJAP, newer ones have AT+CWJAP_CUR and AT+CWHOSTNAME
|
||||
StringFormatter::send(wifiStream, F("AT+CWJAP_CUR?\r\n"));
|
||||
if (!(checkForOK(2000, true))) {
|
||||
use_CUR=false;
|
||||
oldCmd=true;
|
||||
while (wifiStream->available()) StringFormatter::printEscape( wifiStream->read()); /// THIS IS A DIAG IN DISGUISE
|
||||
}
|
||||
}
|
||||
|
||||
StringFormatter::send(wifiStream, F("AT+CWMODE%s=1\r\n"), oldCmd ? "" : "_CUR"); // configure as "station" = WiFi client
|
||||
StringFormatter::send(wifiStream, F("AT+CWMODE%s=1\r\n"), use_CUR ? "_CUR" : ""); // configure as "station" = WiFi client
|
||||
checkForOK(1000, true); // Not always OK, sometimes "no change"
|
||||
|
||||
const char *yourNetwork = "Your network ";
|
||||
@@ -200,29 +208,23 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password,
|
||||
ipOK = true;
|
||||
}
|
||||
} else {
|
||||
// SSID was configured, so we assume station (client) mode.
|
||||
if (oldCmd) {
|
||||
// AT command early version supports CWJAP/CWSAP
|
||||
StringFormatter::send(wifiStream, F("AT+CWJAP=\"%S\",\"%S\"\r\n"), SSid, password);
|
||||
ipOK = checkForOK(WIFI_CONNECT_TIMEOUT, true);
|
||||
} else {
|
||||
// later version supports CWJAP_CUR
|
||||
StringFormatter::send(wifiStream, F("AT+CWHOSTNAME=\"%S\"\r\n"), hostname); // Set Host name for Wifi Client
|
||||
checkForOK(2000, true); // dont care if not supported
|
||||
|
||||
StringFormatter::send(wifiStream, F("AT+CWJAP_CUR=\"%S\",\"%S\"\r\n"), SSid, password);
|
||||
ipOK = checkForOK(WIFI_CONNECT_TIMEOUT, true);
|
||||
}
|
||||
// SSID was configured, so we assume station (client) mode.
|
||||
if (!oldCmd) {
|
||||
StringFormatter::send(wifiStream, F("AT+CWHOSTNAME=\"%S\"\r\n"), hostname); // Set Host name for Wifi Client
|
||||
checkForOK(2000, true); // dont care if not supported
|
||||
}
|
||||
StringFormatter::send(wifiStream, F("AT+CWJAP%s=\"%S\",\"%S\"\r\n"), use_CUR ? "_CUR" : "" , SSid, password);
|
||||
ipOK = checkForOK(WIFI_CONNECT_TIMEOUT, true);
|
||||
|
||||
if (ipOK) {
|
||||
// But we really only have the ESSID and password correct
|
||||
// Let's check for IP (via DHCP)
|
||||
ipOK = false;
|
||||
StringFormatter::send(wifiStream, F("AT+CIFSR\r\n"));
|
||||
if (checkForOK(5000, F("+CIFSR:STAIP"), true,false))
|
||||
if (ipOK) {
|
||||
// But we really only have the ESSID and password correct
|
||||
// Let's check for IP (via DHCP)
|
||||
ipOK = false;
|
||||
StringFormatter::send(wifiStream, F("AT+CIFSR\r\n"));
|
||||
if (checkForOK(5000, F("+CIFSR:STAIP"), true,false))
|
||||
if (!checkForOK(1000, F("0.0.0.0"), true,false))
|
||||
ipOK = true;
|
||||
}
|
||||
ipOK = true;
|
||||
}
|
||||
}
|
||||
|
||||
if (!ipOK) {
|
||||
@@ -235,7 +237,7 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password,
|
||||
do {
|
||||
// configure as AccessPoint. Try really hard as this is the
|
||||
// last way out to get any Wifi connectivity.
|
||||
StringFormatter::send(wifiStream, F("AT+CWMODE%s=2\r\n"), oldCmd ? "" : "_CUR");
|
||||
StringFormatter::send(wifiStream, F("AT+CWMODE%s=2\r\n"), use_CUR ? "_CUR" : "");
|
||||
} while (!checkForOK(1000+i*500, true) && i++<10);
|
||||
|
||||
while (wifiStream->available()) StringFormatter::printEscape( wifiStream->read()); /// THIS IS A DIAG IN DISGUISE
|
||||
@@ -262,10 +264,10 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password,
|
||||
if (STRNCMP_P(yourNetwork, (const char*)password, 13) == 0) {
|
||||
// unconfigured
|
||||
StringFormatter::send(wifiStream, F("AT+CWSAP%s=\"DCCEX_%s\",\"PASS_%s\",%d,4\r\n"),
|
||||
oldCmd ? "" : "_CUR", macTail, macTail, channel);
|
||||
use_CUR ? "_CUR" : "", macTail, macTail, channel);
|
||||
} else {
|
||||
// password configured by user
|
||||
StringFormatter::send(wifiStream, F("AT+CWSAP%s=\"DCCEX_%s\",\"%S\",%d,4\r\n"), oldCmd ? "" : "_CUR",
|
||||
StringFormatter::send(wifiStream, F("AT+CWSAP%s=\"DCCEX_%s\",\"%S\",%d,4\r\n"), use_CUR ? "_CUR" : "",
|
||||
macTail, password, channel);
|
||||
}
|
||||
} while (!checkForOK(WIFI_CONNECT_TIMEOUT, true) && i++<2); // do twice if necessary but ignore failure as AP mode may still be ok
|
||||
|
@@ -4,7 +4,11 @@
|
||||
#include "StringFormatter.h"
|
||||
|
||||
|
||||
#define VERSION "4.2.44"
|
||||
#define VERSION "4.2.48"
|
||||
// 4.2.48 - BROADCAST/WITHROTTLE Exrail macros
|
||||
// 4.2.47 - Correct response to <JA 0>
|
||||
// 4.2.46 - Support boards with inverted fault pin
|
||||
// 4.2.45 - Add ONCLOCKMINS to FastClock to allow hourly repeat events
|
||||
// 4.2.44 - Add PowerShell installer EX-CommandStation-installer.exe
|
||||
// 4.2.43 - Fix STM32 set right port mode bits for analog
|
||||
// 4.2.42 - Added EXRAIL TURNOUTL Macro definition
|
||||
|
Reference in New Issue
Block a user