1
0
mirror of https://github.com/DCC-EX/CommandStation-EX.git synced 2024-12-23 12:51:24 +01:00

various spelling fixes to comments

This commit is contained in:
david zuhn 2024-05-14 13:49:06 -05:00
parent 28d60d4984
commit 2dab0155e2
34 changed files with 111 additions and 108 deletions

View File

@ -33,7 +33,7 @@ For more information just check our code or read https://google.github.io/styleg
1. Clone the repository on your local machine
2. Create a working branch using the format "username-featurename" ex: "git branch -b frightrisk-turnouts"
3. Commit offen, ex: "git add ." and then "git commit -m "description of your changes"
3. Commit often, ex: "git add ." and then "git commit -m "description of your changes"
4. Push your changes to our repository "git push"
5. When you are ready, issue a pull request for your changes to be merged into the main branch
@ -51,7 +51,7 @@ Contributors who do not follow the be nice rule in good faith may face temporary
## How Can I Contribute?
The DCC-EX Team has several projects and sub teams where you can help donate your epertise. See the sections below for the project or projects you are interested in.
The DCC-EX Team has several projects and sub teams where you can help donate your expertise. See the sections below for the project or projects you are interested in.
### Development
### Documentation

View File

@ -67,7 +67,7 @@ void CommandDistributor::parse(byte clientId,byte * buffer, RingStream * stream
ring=stream;
// First check if the client is not known
// yet and in that case determinine type
// yet and in that case determine type
// NOTE: First character of transmission determines if this
// client is using the DCC++ protocol where all commands start
// with '<'
@ -98,7 +98,7 @@ void CommandDistributor::parse(byte clientId,byte * buffer, RingStream * stream
DIAG(F("OUTBOUND FULL processing cmd:%s"),buffer);
}
} else {
DIAG(F("CD parse: was alredy committed")); //XXX Could have been committed by broadcastClient?!
DIAG(F("CD parse: was already committed")); //XXX Could have been committed by broadcastClient?!
}
}

View File

@ -76,7 +76,7 @@ void setup()
DIAG(F("License GPLv3 fsf.org (c) dcc-ex.com"));
// Initialise HAL layer before reading EEprom or setting up MotorDrivers
// 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,
@ -110,7 +110,7 @@ void setup()
// Responsibility 3: Start the DCC engine.
DCC::begin();
// Start RMFT aka EX-RAIL (ignored if no automnation)
// Start RMFT aka EX-RAIL (ignored if no automation)
RMFT::begin();

18
DCC.cpp
View File

@ -43,7 +43,7 @@
// It has no visibility of the hardware, timers, interrupts
// nor of the waveform issues such as preambles, start bits checksums or cutouts.
//
// Nor should it have to deal with JMRI responsess other than the OK/FAIL
// Nor should it have to deal with JMRI responses other than the OK/FAIL
// or cv value returned. I will move that back to the JMRI interface later
//
// The interface to the waveform generator is narrowed down to merely:
@ -250,7 +250,7 @@ void DCC::setAccessory(int address, byte port, bool gate, byte onoff /*= 2*/) {
// >1 => send both on and off packets.
// An accessory has an address, 4 ports and 2 gates (coils) each. That's how
// the initial decoders were orgnized and that influenced how the DCC
// the initial decoders were organized and that influenced how the DCC
// standard was made.
#ifdef DIAG_IO
DIAG(F("DCC::setAccessory(%d,%d,%d)"), address, port, gate);
@ -262,7 +262,7 @@ void DCC::setAccessory(int address, byte port, bool gate, byte onoff /*= 2*/) {
return;
byte b[2];
// first byte is of the form 10AAAAAA, where AAAAAA represent 6 least signifcant bits of accessory address
// first byte is of the form 10AAAAAA, where AAAAAA represent 6 least significant bits of accessory address
// second byte is of the form 1AAACPPG, where C is 1 for on, PP the ports 0 to 3 and G the gate (coil).
b[0] = address % 64 + 128;
b[1] = ((((address / 64) % 8) << 4) + (port % 4 << 1) + gate % 2) ^ 0xF8;
@ -365,7 +365,7 @@ const ackOp FLASH READ_BIT_PROG[] = {
const ackOp FLASH WRITE_BYTE_PROG[] = {
BASELINE,
WB,WACK,ITC1, // Write and callback(1) if ACK
// handle decoders that dont ack a write
// handle decoders that don't ack a write
VB,WACK,ITC1, // validate byte and callback(1) if correct
CALLFAIL // callback (-1)
};
@ -467,7 +467,7 @@ const ackOp FLASH LOCO_ID_PROG[] = {
V0, WACK, MERGE,
V0, WACK, MERGE,
VB, WACK, NAKFAIL, // verify merged byte and return -1 it if not acked ok
COMBINELOCOID, // Combile byte with stash to make long locoid and callback
COMBINELOCOID, // Combine byte with stash to make long locoid and callback
// ITSKIP Skips to here if CV 29 bit 5 was zero. so read CV 1 and return that
SKIPTARGET,
@ -489,7 +489,7 @@ const ackOp FLASH SHORT_LOCO_ID_PROG[] = {
BASELINE,
SETCV,(ackOp)19,
SETBYTE, (ackOp)0,
WB,WACK, // ignore dedcoder without cv19 support
WB,WACK, // ignore decoder without cv19 support
// Turn off long address flag
SETCV,(ackOp)29,
SETBIT,(ackOp)5,
@ -632,12 +632,12 @@ bool DCC::issueReminder(int reg) {
case 4: // remind function group 4 F13-F20
if (flags & FN_GROUP_4)
setFunctionInternal(loco,222, ((functions>>13)& 0xFF));
flags&= ~FN_GROUP_4; // dont send them again
flags&= ~FN_GROUP_4; // don't send them again
break;
case 5: // remind function group 5 F21-F28
if (flags & FN_GROUP_5)
setFunctionInternal(loco,223, ((functions>>21)& 0xFF));
flags&= ~FN_GROUP_5; // dont send them again
flags&= ~FN_GROUP_5; // don't send them again
break;
}
loopStatus++;
@ -691,7 +691,7 @@ int DCC::lookupSpeedTable(int locoId, bool autoCreate) {
void DCC::updateLocoReminder(int loco, byte speedCode) {
if (loco==0) {
// broadcast stop/estop but dont change direction
// broadcast stop/estop but don't change direction
for (int reg = 0; reg <= highestUsedReg; reg++) {
if (speedTable[reg].loco==0) continue;
byte newspeed=(speedTable[reg].speedCode & 0x80) | (speedCode & 0x7f);

View File

@ -77,12 +77,12 @@ void DCCACK::Setup(int cv, byte byteValueOrBitnum, ackOp const program[], ACK_C
progDriver=TrackManager::getProgDriver();
if (progDriver==NULL) {
TrackManager::setJoin(ackManagerRejoin);
callback(-3); // we dont have a prog track!
callback(-3); // we don't have a prog track!
return;
}
if (!progDriver->canMeasureCurrent()) {
TrackManager::setJoin(ackManagerRejoin);
callback(-2); // our prog track cant measure current
callback(-2); // our prog track can't measure current
return;
}
@ -117,7 +117,7 @@ void DCCACK::Setup(int wordval, ackOp const program[], ACK_CALLBACK callback) {
const byte RESET_MIN=8; // tuning of reset counter before sending message
// checkRessets return true if the caller should yield back to loop and try later.
// checkResets return true if the caller should yield back to loop and try later.
bool DCCACK::checkResets(uint8_t numResets) {
return DCCWaveform::progTrack.getResets() < numResets;
}
@ -223,7 +223,7 @@ void DCCACK::loop() {
break; // we have a genuine ACK result
}
case ITC0:
case ITC1: // If True Callback(0 or 1) (if prevous WACK got an ACK)
case ITC1: // If True Callback(0 or 1) (if previous WACK got an ACK)
if (ackReceived) {
callback(opcode==ITC0?0:1);
return;
@ -375,8 +375,8 @@ void DCCACK::callback(int value) {
if (millis()-callbackStart < 100) break;
// stable after power maintained for 100mS
// If we are going to power off anyway, it doesnt matter
// but if we will keep the power on, we must off it for 30mS
// If we are going to power off anyway, it doesn't matter
// but if we will keep the power on, we must turn it off for 30mS
if (autoPowerOff) callbackState=READY;
else { // Need to cycle power off and on
progDriver->setPower(POWERMODE::OFF);

View File

@ -176,7 +176,7 @@ RingStream *DCCEXParser::stashRingStream = NULL;
byte DCCEXParser::stashTarget=0;
// This is a JMRI command parser.
// It doesnt know how the string got here, nor how it gets back.
// It doesn't know how the string got here, nor how it gets back.
// It knows nothing about hardware or tracks... it just parses strings and
// calls the corresponding DCC api.
// Non-DCC things like turnouts, pins and sensors are handled in additional JMRI interface classes.
@ -625,12 +625,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
return;
#ifndef DISABLE_EEPROM
case 'E': // STORE EPROM <E>
case 'E': // STORE EEPROM <E>
EEStore::store();
StringFormatter::send(stream, F("<e %d %d %d>\n"), EEStore::eeStore->data.nTurnouts, EEStore::eeStore->data.nSensors, EEStore::eeStore->data.nOutputs);
return;
case 'e': // CLEAR EPROM <e>
case 'e': // CLEAR EEPROM <e>
EEStore::clear();
StringFormatter::send(stream, F("<O>\n"));
return;
@ -980,7 +980,7 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
{
if (params == 0)
return false;
bool onOff = (params > 0) && (p[1] == 1 || p[1] == HASH_KEYWORD_ON); // dont care if other stuff or missing... just means off
bool onOff = (params > 0) && (p[1] == 1 || p[1] == HASH_KEYWORD_ON); // don't care if other stuff or missing... just means off
switch (p[0])
{
case HASH_KEYWORD_CABS: // <D CABS>
@ -1042,7 +1042,7 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
#endif
case HASH_KEYWORD_RESET:
DCCTimer::reset();
break; // and <X> if we didnt restart
break; // and <X> if we didn't restart
#ifndef DISABLE_EEPROM

View File

@ -123,10 +123,13 @@ RMTChannel::RMTChannel(pinpair pins, bool isMain) {
config.channel = channel = (rmt_channel_t)ch;
config.clk_div = RMT_CLOCK_DIVIDER;
config.gpio_num = (gpio_num_t)pins.pin;
config.mem_block_num = 2; // With longest DCC packet 11 inc checksum (future expansion)
// number of bits needed is 22preamble + start +
// 11*9 + extrazero + EOT = 124
// 2 mem block of 64 RMT items should be enough
// With longest DCC packet (11 bytes, including checksum (future expansion)):
// number of bits needed is PREAMBLE_BITS_PROG (22) + start (1) +
// data bytes (11*9) + extrazero (1) + EOT (1) = 124
//
// 2 mem blocks of 64 RMT items should be enough
config.mem_block_num = 2;
ESP_ERROR_CHECK(rmt_config(&config));
addPin(pins.invpin, true);
@ -166,7 +169,7 @@ const byte transmitMask[] = {0x80, 0x40, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01};
int RMTChannel::RMTfillData(const byte buffer[], byte byteCount, byte repeatCount=0) {
//int RMTChannel::RMTfillData(dccPacket packet) {
// dataReady: Signals to then interrupt routine. It is set when
// dataReady: Signals to the interrupt routine. It is set when
// we have data in the channel buffer which can be copied out
// to the HW. dataRepeat on the other hand signals back to
// the caller of this function if the data has been sent enough

View File

@ -44,7 +44,7 @@
* Other shields may be jumpered to PWM pins or run directly using the software interrupt.
*
* Because the PWM-based waveform is effectively set half a cycle after the software version,
* it is not acceptable to drive the two tracks on different methiods or it would cause
* it is not acceptable to drive the two tracks on different methods or it would cause
* problems for <1 JOIN> etc.
*
*/
@ -98,7 +98,7 @@ private:
// Class ADCee implements caching of the ADC value for platforms which
// have a too slow ADC read to wait for. On these platforms the ADC is
// scanned continiously in the background from an ISR. On such
// scanned continuously in the background from an ISR. On such
// architectures that use the analog read during DCC waveform with
// specially configured ADC, for example AVR, init must be called
// PRIOR to the start of the waveform. It returns the current value so

View File

@ -121,7 +121,7 @@ int DCCTimer::freeMemory() {
void DCCTimer::reset() {
wdt_enable( WDTO_15MS); // set Arduino watchdog timer for 15ms
delay(50); // wait for the prescaller time to expire
delay(50); // wait for the prescaler time to expire
}
@ -210,7 +210,7 @@ void ADCee::scan() {
// look for a valid track to sample or until we are around
while (true) {
if (mask & usedpins) {
// start new ADC aquire on id
// start new ADC acquire on id
#if defined(ADCSRB) && defined(MUX5)
if (ADCusesHighPort) { // if we ever have started to use high pins)
if (id > 7) // if we use a high ADC pin

View File

@ -73,7 +73,7 @@ int DCCTimer::getMinimumFreeMemory() {
int DCCTimer::freeMemory() {
return ESP.getFreeHeap();
}
#endif
#endif // ESP8266
////////////////////////////////////////////////////////////////////////
@ -114,7 +114,7 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
timerAlarmEnable(timer);
}
// We do not support to use PWM to make the Waveform on ESP
// We do not support using PWM to make the Waveform on ESP
bool IRAM_ATTR DCCTimer::isPWMPin(byte pin) {
return false;
}

View File

@ -44,7 +44,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 additional serial ports defined by default
// On the F446RE, Serial1 isn't really useable as it's Rx/Tx pair sit on already used D2/D10 pins
// On the F446RE, Serial1 isn't really useable as its Rx/Tx pair sit on already used D2/D10 pins
// 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.
@ -369,7 +369,7 @@ void ADCee::scan() {
// look for a valid track to sample or until we are around
while (true) {
if (mask & usedpins) {
// start new ADC aquire on id
// start new ADC acquire on id
ADC1->SQR3 = analogchans[id]; //1st conversion in regular sequence
ADC1->CR2 |= (1 << 30); //Start 1st conversion SWSTART
#ifdef DEBUG_ADC

View File

@ -52,7 +52,7 @@ void DCCTimer::setPWM(byte pin, bool high) {
}
void DCCTimer::clearPWM() {
// Do nothing unless we implent HA
// Do nothing unless we implement HA
}
#if defined(__IMXRT1062__) //Teensy 4.0 and Teensy 4.1

View File

@ -36,7 +36,7 @@ DCCWaveform DCCWaveform::mainTrack(PREAMBLE_BITS_MAIN, true);
DCCWaveform DCCWaveform::progTrack(PREAMBLE_BITS_PROG, false);
// This bitmask has 9 entries as each byte is trasmitted as a zero + 8 bits.
// This bitmask has 9 entries as each byte is transmitted as a zero + 8 bits.
const byte bitMask[] = {0x00, 0x80, 0x40, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01};
const byte idlePacket[] = {0xFF, 0x00, 0xFF};
@ -88,7 +88,7 @@ void DCCWaveform::interruptHandler() {
mainTrack.state=stateTransform[mainTrack.state];
progTrack.state=stateTransform[progTrack.state];
// WAVE_PENDING means we dont yet know what the next bit is
// WAVE_PENDING means we don't yet know what the next bit is
if (mainTrack.state==WAVE_PENDING) mainTrack.interrupt2();
if (progTrack.state==WAVE_PENDING) progTrack.interrupt2();
else DCCACK::checkAck(progTrack.getResets());
@ -99,7 +99,7 @@ void DCCWaveform::interruptHandler() {
// An instance of this class handles the DCC transmissions for one track. (main or prog)
// Interrupts are marshalled via the statics.
// A track has a current transmit buffer, and a pending buffer.
// When the current buffer is exhausted, either the pending buffer (if there is one waiting) or an idle buffer.
// When the current buffer is exhausted, send either the pending buffer (if there is one waiting) or an idle buffer.
@ -144,7 +144,7 @@ void DCCWaveform::interrupt2() {
//end of Byte
bits_sent = 0;
bytes_sent++;
// if this is the last byte, prepere for next packet
// if this is the last byte, prepare for next packet
if (bytes_sent >= transmitLength) {
// end of transmission buffer... repeat or switch to next message
bytes_sent = 0;
@ -247,7 +247,7 @@ void DCCWaveform::schedulePacket(const byte buffer[], byte byteCount, byte repea
pendingPacket[byteCount] = checksum;
pendingLength = byteCount + 1;
pendingRepeats = repeats;
// DIAG repeated commands (accesories)
// DIAG repeated commands (accessories)
// if (pendingRepeats > 0)
// DIAG(F("Repeats=%d on %s track"), pendingRepeats, isMainTrack ? "MAIN" : "PROG");
// The resets will be zero not only now but as well repeats packets into the future

View File

@ -70,7 +70,7 @@ const int16_t HASH_KEYWORD_RED=26099;
const int16_t HASH_KEYWORD_AMBER=18713;
const int16_t HASH_KEYWORD_GREEN=-31493;
// One instance of RMFT clas is used for each "thread" in the automation.
// One instance of RMFT class is used for each "thread" in the automation.
// Each thread manages a loco on a journey through the layout, and/or may manage a scenery automation.
// The threads exist in a ring, each time through loop() the next thread in the ring is serviced.
@ -1145,7 +1145,7 @@ void RMFT2::handleEvent(const FSH* reason,LookList* handlers, int16_t id) {
int pc= handlers->find(id);
if (pc<0) return;
// Check we dont already have a task running this handler
// Check we don't already have a task running this handler
RMFT2 * task=loopTask;
while(task) {
if (task->onEventStartPosition==pc) {
@ -1231,8 +1231,8 @@ void RMFT2::thrungeString(uint32_t strfar, thrunger mode, byte id) {
stream->write(c);
}
#else
// UNO/NANO CPUs dont have high memory
// 32 bit cpus dont care anyway
// UNO/NANO CPUs don't have high memory
// 32 bit cpus don't care anyway
stream->print((FSH *)strfar);
#endif

View File

@ -96,7 +96,7 @@ void I2CManagerClass::begin(void) {
setTimeout(1000); // use 1ms timeout for probes
#if defined(I2C_EXTENDED_ADDRESS)
// First count the multiplexers and switch off all subbuses
// First count the multiplexers and switch off all subBuses
_muxCount = 0;
for (uint8_t muxNo=I2CMux_0; muxNo <= I2CMux_7; muxNo++) {
if (I2CManager.muxSelectSubBus({(I2CMux)muxNo, SubBus_None})==I2C_STATUS_OK)
@ -117,8 +117,8 @@ void I2CManagerClass::begin(void) {
// Enumerate all I2C devices that are connected via multiplexer,
// i.e. that respond when only one multiplexer has one subBus enabled
// and the device doesn't respond when the mux subBus is disabled.
// If any probes time out, then assume that the subbus is dead and
// don't do any more on that subbus.
// If any probes time out, then assume that the subBus is dead and
// don't do any more on that subBus.
for (uint8_t muxNo=I2CMux_0; muxNo <= I2CMux_7; muxNo++) {
uint8_t muxAddr = I2C_MUX_BASE_ADDRESS + muxNo;
if (exists(muxAddr)) {
@ -131,8 +131,8 @@ void I2CManagerClass::begin(void) {
// De-select subbus
muxSelectSubBus({(I2CMux)muxNo, SubBus_None});
if (!exists(addr)) {
// Device responds when subbus selected but not when
// subbus disabled - ergo it must be on subbus!
// Device responds when subBus selected but not when
// subbus disabled - ergo it must be on subBus!
found = true;
DIAG(F("I2C Device found at {I2CMux_%d,SubBus_%d,0x%x}, %S?"),
muxNo, subBus, addr, guessI2CDeviceType(addr));

View File

@ -171,7 +171,7 @@ enum I2CSubBus : uint8_t {
SubBus_7 = 7,
#endif
#endif
SubBus_No, // Number of subbuses (highest + 1)
SubBus_No, // Number of sub-buses (highest + 1)
SubBus_None = 254, // Disable all sub-buses on selected mux
SubBus_All = 255, // Enable all sub-buses (not supported by some multiplexers)
};
@ -344,7 +344,7 @@ private:
void toHex(const uint8_t value, char *buffer);
void addressWarning() {
if (!_addressWarningDone) {
DIAG(F("WARNIING: Extended I2C address used but not supported in this configuration"));
DIAG(F("WARNING: Extended I2C address used but not supported in this configuration"));
_addressWarningDone = true;
}
}
@ -430,7 +430,7 @@ public:
void setClock(uint32_t speed);
// Force clock speed
void forceClock(uint32_t speed);
// setTimeout sets the timout value for I2C transactions (milliseconds).
// setTimeout sets the timeout value for I2C transactions (milliseconds).
void setTimeout(unsigned long);
// Check if specified I2C address is responding.
uint8_t checkAddress(I2CAddress address);

View File

@ -329,7 +329,7 @@ IODevice *IODevice::findDeviceFollowing(VPIN vpin) {
}
// Private helper function to check for vpin overlap. Run during setup only.
// returns true if pins DONT overlap with existing device
// returns true if pins DO NOT overlap with existing device
// TODO: Move the I2C address reservation and checks into the I2CManager code.
// That will enable non-HAL devices to reserve I2C addresses too.
bool IODevice::checkNoOverlap(VPIN firstPin, uint8_t nPins, I2CAddress i2cAddress) {

View File

@ -83,7 +83,7 @@ private:
void _begin() {
uint8_t status;
// Initialise EX-IOExander device
// Initialise EX-IOExpander device
I2CManager.begin();
if (I2CManager.exists(_I2CAddress)) {
// Send config, if EXIOPINS returned, we're good, setup pin buffers, otherwise go offline
@ -252,7 +252,7 @@ private:
// changes and notify them to subscribers, to avoid the need for polling - see IO_GPIOBase.h).
}
} else
reportError(status, false); // report eror but don't go offline.
reportError(status, false); // report error but don't go offline.
_readState = RDS_IDLE;
}

View File

@ -112,7 +112,7 @@ void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_
I2CManager.write(_I2CAddress, 3, stepsMSB, stepsLSB, activity);
}
// Display Turnetable-EX device driver info.
// Display Turntable-EX device driver info.
void EXTurntable::_display() {
DIAG(F("EX-Turntable I2C:%s Configured on Vpins:%u-%u %S"), _I2CAddress.toString(), (int)_firstVpin,
(int)_firstVpin+_nPins-1, (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F(""));

View File

@ -80,7 +80,7 @@ private:
// Initiate the device
void _begin() {
uint8_t _status;
// Attempt to initilalise device
// Attempt to initialise device
I2CManager.begin();
if (I2CManager.exists(_I2CAddress)) {
// Send RE_RDY, must receive RE_RDY to be online

View File

@ -102,7 +102,7 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
getFastPin(F("BRAKE"),brakePin,fastBrakePin);
// if brake is used for railcom cutout we need to do PORTX register trick here as well
pinMode(brakePin, OUTPUT);
setBrake(true); // start with brake on in case we hace DC stuff going on
setBrake(true); // start with brake on in case we have DC stuff going on
} else {
brakePin=UNUSED_PIN;
}
@ -132,7 +132,7 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
}
// This conversion performed at compile time so the remainder of the code never needs
// float calculations or libraray code.
// float calculations or library code.
senseFactorInternal=sense_factor * senseScale;
tripMilliamps=trip_milliamps;
#ifdef MAX_CURRENT
@ -145,7 +145,7 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
// This would mean that the values obtained from the ADC never
// can reach the trip value. So independent of the current, the
// short circuit protection would never trip. So we adjust the
// trip value so that it is tiggered when the ADC reports it's
// trip value so that it is triggered when the ADC reports its
// maximum value instead.
// DIAG(F("Changing short detection value from %d to %d mA"),
@ -179,7 +179,7 @@ void MotorDriver::setPower(POWERMODE mode) {
globalOverloadStart = lastPowerChange[(int)mode];
bool on=(mode==POWERMODE::ON || mode ==POWERMODE::ALERT);
if (on) {
// when switching a track On, we need to check the crrentOffset with the pin OFF
// when switching a track On, we need to check the currentOffset with the pin OFF
if (powerMode==POWERMODE::OFF && currentPin!=UNUSED_PIN) {
senseOffset = ADCee::read(currentPin);
DIAG(F("Track %c sensOffset=%d"),trackLetter,senseOffset);
@ -247,7 +247,7 @@ int MotorDriver::getCurrentRaw(bool fromISR) {
/*
* This should only be called in interrupt context
* Copies current value from HW to cached value in
* Motordriver.
* MotorDriver.
*/
#pragma GCC push_options
#pragma GCC optimize ("-O3")
@ -293,7 +293,7 @@ void MotorDriver::setDCSignal(byte speedcode) {
return;
switch(brakePin) {
#if defined(ARDUINO_AVR_UNO)
// Not worth doin something here as:
// Not worth doing something here as:
// If we are on pin 9 or 10 we are on Timer1 and we can not touch Timer1 as that is our DCC source.
// If we are on pin 5 or 6 we are on Timer 0 ad we can not touch Timer0 as that is millis() etc.
// We are most likely not on pin 3 or 11 as no known motor shield has that as brake.
@ -324,7 +324,7 @@ void MotorDriver::setDCSignal(byte speedcode) {
default:
break;
}
// spedcoode is a dcc speed & direction
// speedcoode is a dcc speed & direction
byte tSpeed=speedcode & 0x7F; // DCC Speed with 0,1 stop and speed steps 2 to 127
byte tDir=speedcode & 0x80;
byte brake;
@ -461,7 +461,7 @@ void MotorDriver::getFastPin(const FSH* type,int pin, bool input, FASTPIN & res
///////////////////////////////////////////////////////////////////////////////////////////
// checkPowerOverload(useProgLimit, trackno)
// bool useProgLimit: Trackmanager knows if this track is in prog mode or in main mode
// byte trackno: trackmanager knows it's number (could be skipped?)
// byte trackno: trackmanager knows its number (could be skipped?)
//
// Short ciruit handling strategy:
//

View File

@ -78,7 +78,7 @@
#elif defined(ARDUINO_ARCH_ESP32)
// STANDARD shield on an ESPDUINO-32 (ESP32 in Uno form factor). The shield must be eiter the
// STANDARD shield on an ESPDUINO-32 (ESP32 in Uno form factor). The shield must be either the
// 3.3V compatible R3 version or it has to be modified to not supply more than 3.3V to the
// 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
@ -118,7 +118,7 @@
// pins 9 and 10 work as "inverted brake" but as we turn on and off the tracks individually
// via the power pins we above use 9 and 10 as power pins and 4 as "inverted brake" which in this
// version of the code always will be high. That means this config is not usable for generating
// a railcom cuotout in the future. For that one must wire the second ^D2 to pin 2 and define
// a railcom cutout in the future. For that one must wire the second ^D2 to pin 2 and define
// the motor driver like this:
// new MotorDriver(4, 7, UNUSED_PIN, -9, A0, 18, 3000, 12)
// new MotorDriver(2, 8, UNUSED_PIN, -10, A1, 18, 3000, 12)
@ -171,7 +171,7 @@
new MotorDriver(5, 4, UNUSED_PIN, UNUSED_PIN, UNUSED_PIN, 1.0, 1100, UNUSED_PIN)
// This is an example how to setup a motor shield definition for a motor shield connected
// to an NANO EVERY board. You have to make the connectons from the shield to the board
// to an NANO EVERY board. You have to make the connections from the shield to the board
// as in this example or adjust the values yourself.
#define NANOEVERY_EXAMPLE F("NANOEVERY_EXAMPLE"), \
new MotorDriver(5, 6, UNUSED_PIN, UNUSED_PIN, A0, 2.99, 1500, UNUSED_PIN),\
@ -180,7 +180,7 @@
// This is an example how to stack two standard motor shields. The upper shield
// needs pins 3 8 9 11 12 13 A0 A1 disconnected from the lower shield and
// jumpered instead like this: 2-3 6-8 7-9 4-13 5-11 10-12 A0-A4 A1-A5
// Pin assigment table:
// Pin assignment table:
// 2 Enable C jumpered
// 3 Enable A direct
// 4 Dir D jumpered

View File

@ -23,7 +23,7 @@
/**********************************************************************
DCC++ BASE STATION supports optional OUTPUT control of any unused Arduino Pins for custom purposes.
Pins can be activited or de-activated. The default is to set ACTIVE pins HIGH and INACTIVE pins LOW.
Pins can be activated or de-activated. The default is to set ACTIVE pins HIGH and INACTIVE pins LOW.
However, this default behavior can be inverted for any pin in which case ACTIVE=LOW and INACTIVE=HIGH.
Definitions and state (ACTIVE/INACTIVE) for pins are retained in EEPROM and restored on power-up.
@ -35,9 +35,9 @@ To have this sketch utilize one or more Arduino pins as custom outputs, first de
output definitions using the following variation of the "Z" command:
<Z ID PIN IFLAG>: creates a new output ID, with specified PIN and IFLAG values.
if output ID already exists, it is updated with specificed PIN and IFLAG.
if output ID already exists, it is updated with specified PIN and IFLAG.
note: output state will be immediately set to ACTIVE/INACTIVE and pin will be set to HIGH/LOW
according to IFLAG value specifcied (see below).
according to IFLAG value specified (see below).
returns: <O> if successful and <X> if unsuccessful (e.g. out of memory)
<Z ID>: deletes definition of output ID
@ -61,8 +61,8 @@ where
1 = state of pin set on power-up, or when first created, to either ACTIVE of INACTIVE
depending on IFLAG, bit 2
IFLAG, bit 2: 0 = state of pin set to INACTIVE uponm power-up or when first created
1 = state of pin set to ACTIVE uponm power-up or when first created
IFLAG, bit 2: 0 = state of pin set to INACTIVE upon power-up or when first created
1 = state of pin set to ACTIVE upon power-up or when first created
Once all outputs have been properly defined, use the <E> command to store their definitions to EEPROM.
If you later make edits/additions/deletions to the output definitions, you must invoke the <E> command if you want those

View File

@ -6,7 +6,7 @@ Currently, our products include the following:
* [EX-CommandStation](https://github.com/DCC-EX/CommandStation-EX/releases)
* [EX-WebThrottle](https://github.com/DCC-EX/exWebThrottle)
* [EX-Installer](https://github.com/DCC-EX/EX-Installer)
* [EX-MotoShield8874](https://dcc-ex.com/reference/hardware/motorboards/ex-motor-shield-8874.html#gsc.tab=0)
* [EX-MotorShield8874](https://dcc-ex.com/reference/hardware/motorboards/ex-motor-shield-8874.html#gsc.tab=0)
* [EX-DCCInspector](https://github.com/DCC-EX/DCCInspector-EX)
* [EX-Toolbox](https://github.com/DCC-EX/EX-Toolbox)
* [EX-Turntable](https://github.com/DCC-EX/EX-Turntable)
@ -18,7 +18,7 @@ Details of these projects can be found on [our web site](https://dcc-ex.com/).
# Whats in this Repository?
This repository, CommandStation-EX, contains a complete DCC-EX *EX-CommmandStation* sketch designed for compiling and uploading into an Arduino Uno, Mega, or Nano.
This repository, CommandStation-EX, contains a complete DCC-EX *EX-CommandStation* sketch designed for compiling and uploading into an Arduino Uno, Mega, or Nano.
To utilize this sketch, you can use the following:

View File

@ -15,7 +15,7 @@ Track Manger (TM from now on) is an integral part of DCC++EX software that is re
- Intercepting throttle commands to locos running on DC tracks.
- Handling user or EXRAIL commands to switch track status.
In the default scenario of a single DCC track and a PROG track, the TM behaves as for the previous versions of DCC++EX so if thats what you want, you dont need to mess with it.
In the default scenario of a single DCC track and a PROG track, the TM behaves as for the previous versions of DCC++EX so if thats what you want, you don't need to mess with it.
The TM is able to handle up to 8 separate track domains. Each domain requires a hardware driver to supply track voltage. A typical motor driver shield supplies two tracks, which is what we have used in the past as main and prog.
@ -97,7 +97,7 @@ The easiest way to consider the wiring is to treat each track individually (eith
You will require,for each track, on the Arduino:
- A GPIO pin (or a HAL vpin perhaps on an I2C extender, code TBA!!!) to switch power.
- A GPIO pin to switch the signal direction
- A GPIO pin with PWM capability to switch the Brake (you may omit this if you dont want any DC capability)
- A GPIO pin with PWM capability to switch the Brake (you may omit this if you don't want any DC capability)
- Optionally An Analog pin to read the current (unless your hardware cant do that, perhaps its just feeding a booster)
- Optionally a GPIO fault pin if thats how your hardware works. (NOT recommended as you're going to run out of pins)

View File

@ -21,7 +21,7 @@
// NOTE: The use of a marker byte without an escape algorithm means
// RingStream is unsuitable for binary data. Should binary data need to be
// streamed it will be necessary to implementr an escape strategy to handle the
// streamed it will be necessary to implement an escape strategy to handle the
// marker char when embedded in data.
#include "RingStream.h"

View File

@ -31,11 +31,11 @@ class RingStream : public Print {
virtual size_t write(uint8_t b);
// This availableForWrite function is subverted from its original intention so that a caller
// can destinguish between a normal stream and a RingStream.
// can distinguish between a normal stream and a RingStream.
// The Arduino compiler does not support runtime dynamic cast to perform
// an instranceOf check.
// an instanceOf check.
// This is necessary since the Print functions are mostly not virtual so
// we cant override the print(__FlashStringHelper *) function.
// we can't override the print(__FlashStringHelper *) function.
virtual int availableForWrite() override;
using Print::write;
size_t printFlash(const FSH * flashBuffer);

View File

@ -81,7 +81,7 @@ public:
static void checkAll();
static void printAll(Print *stream);
static unsigned long lastReadCycle; // value of micros at start of last read cycle
static const unsigned int cycleInterval = 10000; // min time between consecutive reads of each sensor in microsecs.
static const unsigned int cycleInterval = 10000; // min time between consecutive reads of each sensor in microseconds.
// should not be less than device scan cycle time.
static const unsigned int minReadCount = 1; // number of additional scans before acting on change
// E.g. 1 means that a change is ignored for one scan and actioned on the next.

View File

@ -76,8 +76,8 @@ void TrackManager::sampleCurrent() {
if (tr > lastTrack) tr = 0;
if (lastTrack < 2 || track[tr]->getMode() & TRACK_MODE_PROG) {
return; // We could continue but for prog track we
// rather do it in next interrupt beacuse
// that gives us well defined sampling point.
// rather do it in next interrupt because
// that gives us a well defined sampling point.
// For other tracks we care less unless we
// have only few (max 2) tracks.
}
@ -231,14 +231,14 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
}
track[trackToSet]->makeProgTrack(true); // set for prog track special handling
} else {
track[trackToSet]->makeProgTrack(false); // only the prog track knows it's type
track[trackToSet]->makeProgTrack(false); // only the prog track knows its type
}
track[trackToSet]->setMode(mode);
trackDCAddr[trackToSet]=dcAddr;
streamTrackState(NULL,trackToSet);
// When a track is switched, we must clear any side effects of its previous
// state, otherwise trains run away or just dont move.
// state, otherwise trains run away or just don't move.
// This can be done BEFORE the PWM-Timer evaluation (methinks)
if (!(mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX)) {
@ -374,7 +374,7 @@ void TrackManager::streamTrackState(Print* stream, byte t) {
format=F("<= %c DCX %d>\n");
break;
default:
break; // unknown, dont care
break; // unknown, don't care
}
if (stream) StringFormatter::send(stream,format,'A'+t,trackDCAddr[t]);
else CommandDistributor::broadcastTrackState(format,'A'+t,trackDCAddr[t]);

View File

@ -393,7 +393,7 @@ void WiThrottle::checkHeartbeat(RingStream * stream) {
if (myLocos[loco].throttle!='\0') {
if (Diag::WITHROTTLE) DIAG(F("%l eStopping cab %d"),millis(),myLocos[loco].cab);
DCC::setThrottle(myLocos[loco].cab, 1, DCC::getThrottleDirection(myLocos[loco].cab)); // speed 1 is eStop
heartBeat=millis(); // We have just stopped everyting, we don't need to do that again at next loop.
heartBeat=millis(); // We have just stopped everything, we don't need to do that again at next loop.
}
}
// if it does come back, the throttle should re-acquire
@ -419,7 +419,7 @@ void WiThrottle::checkHeartbeat(RingStream * stream) {
StringFormatter::send(stream,F("M%cA%c%d<;>R%d\n"),
throttle, lors , cab, DCC::getThrottleDirection(cab));
// compare the DCC functionmap with the local copy and send changes
// compare the DCC function map with the local copy and send changes
uint32_t dccFunctionMap=DCC::getFunctionMap(cab);
uint32_t myFunctionMap=myLocos[loco].functionMap;
myLocos[loco].functionMap=dccFunctionMap;

View File

@ -136,7 +136,7 @@ bool WifiESP::setup(const char *SSid,
// clean start
WiFi.mode(WIFI_STA);
WiFi.disconnect(true);
// differnet settings that did not improve for haba
// different settings that did not improve for haba
// WiFi.useStaticBuffers(true);
// WiFi.setScanMethod(WIFI_ALL_CHANNEL_SCAN);
// WiFi.setSortMethod(WIFI_CONNECT_AP_BY_SECURITY);
@ -376,7 +376,7 @@ void WifiESP::loop() {
// is not necessarily yielding to a low
// prio task. On core1 this is not a problem
// as there the wdt is disabled by the
// arduio IDE startup routines.
// arduino IDE startup routines.
if (xPortGetCoreID() == 0)
feedTheDog0();
yield();

View File

@ -120,7 +120,7 @@ bool WifiInterface::setup(long serial_link_speed,
#endif
#endif
// We guess here that in all architctures that have a Serial3
// We guess here that in all architectures that have a Serial3
// we can use it for our purpose.
#if NUM_SERIAL > 2 && !defined(SERIAL3_COMMANDS)
if (wifiUp == WIFI_NOAT)
@ -255,7 +255,7 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password,
} 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
checkForOK(2000, true); // don't care if not supported
StringFormatter::send(wifiStream, F("AT+CWJAP_CUR=\"%S\",\"%S\"\r\n"), SSid, password);
ipOK = checkForOK(WIFI_CONNECT_TIMEOUT, true);
@ -340,7 +340,7 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password,
if(!oldCmd) { // no idea to test this on old firmware
StringFormatter::send(wifiStream, F("AT+MDNS=1,\"%S\",\"withrottle\",%d\r\n"),
hostname, port); // mDNS responder
checkForOK(1000, true); // dont care if not supported
checkForOK(1000, true); // don't care if not supported
}
StringFormatter::send(wifiStream, F("AT+CIPSERVER=1,%d\r\n"), port); // turn on server on port
@ -379,7 +379,7 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password,
// This function is used to allow users to enter <+ commands> through the DCCEXParser
// <+command> sends AT+command to the ES and returns to the caller.
// Once the user has made whatever changes to the AT commands, a <+X> command can be used
// to force on the connectd flag so that the loop will start picking up wifi traffic.
// to force on the connected flag so that the loop will start picking up wifi traffic.
// If the settings are corrupted <+RST> will clear this and then you must restart the arduino.
// Using the <+> command with no command string causes the code to enter an echo loop so that all
@ -410,7 +410,7 @@ void WifiInterface::ATCommand(HardwareSerial * stream,const byte * command) {
if (*command=='X') {
connected = true;
DIAG(F("++++++ Wifi Connction forced on ++++++++"));
DIAG(F("++++++ Wifi Connection forced on ++++++++"));
}
else {
StringFormatter:: send(wifiStream, F("AT+%s\r\n"), command);

View File

@ -64,7 +64,7 @@ The configuration file for DCC-EX Command Station
// If you want to restrict the maximum current LOWER than what your
// motor shield can provide, you can do that here. For example if you
// have a motor shield that can provide 5A and your power supply can
// only provide 2.5A then you should restict the maximum current to
// only provide 2.5A then you should restrict the maximum current to
// 2.25A (90% of 2.5A) so that DCC-EX does shut off the track before
// your PS does shut DCC-EX. MAX_CURRENT is in mA so for this example
// it would be 2250, adjust the number according to your PS. If your
@ -224,7 +224,7 @@ The configuration file for DCC-EX Command Station
// If you have issues with that the direction of the accessory commands is
// reversed (for example when converting from another CS to DCC-EX) then
// you can use this to reverse the sense of all accessory commmands sent
// you can use this to reverse the sense of all accessory commands sent
// over DCC++. This #define likewise inverts the behaviour of the <a> command
// for triggering DCC Accessory Decoders, so that <a addr subaddr 0> generates a
// DCC packet with D=1 (close turnout) and <a addr subaddr 1> generates D=0

View File

@ -17,7 +17,7 @@
// 5.0.0 - Make 4.2.69 the 5.0.0 release
// 4.2.69 - Bugfix: Make <!> work in DC mode
// 4.2.68 - Rename track mode OFF to NONE
// 4.2.67 - AVR: Pin specific timer register seting
// 4.2.67 - AVR: Pin specific timer register setting
// - Protect Uno user from choosing DC(X)
// - More Nucleo variant defines
// - GPIO PCA9555 / TCA9555 support
@ -68,7 +68,7 @@
// 4.2.34 - Completely fix EX-IOExpander analogue inputs
// 4.2.33 - Fix EX-IOExpander non-working analogue inputs
// 4.2.32 - Fix LCD/Display bugfixes from 4.2.29
// 4.2.31 - Removes EXRAIL statup from top of file. (BREAKING CHANGE !!)
// 4.2.31 - Removes EXRAIL startup from top of file. (BREAKING CHANGE !!)
// Just add AUTOSTART to the top of your myAutomation.h to restore this function.
// 4.2.30 - Fixes/enhancements to EX-IOExpander device driver.
// 4.2.29 - Bugfix Scroll LCD without empty lines and consistent
@ -189,7 +189,7 @@
// EX-RAIL “ROSTER” Engines Id & Function key layout on Engine Driver or WiThrottle
// EX-RAIL DCC++EX Commands to Control EX-RAIL via JMRI Send pane and IDE Serial monitors
// New JMRI feature enhancements;
// Reads DCC++EX EEPROM & automatically uploades any Signals, DCC Turnouts, Servo Turnouts, Vpin Turnouts , & Output pane
// Reads DCC++EX EEPROM & automatically uploads any Signals, DCC Turnouts, Servo Turnouts, Vpin Turnouts , & Output pane
// Turnout class revised to expand turnout capabilities, new commands added.
// Provides for multiple additional DCC++EX WiFi connections as accessory controllers or CS for a programming track when Motor Shields are added
// Supports Multiple Command Station connections and individual tracking of Send DCC++ Command panes and DCC++ Traffic Monitor panes
@ -213,7 +213,7 @@
// Can define border between long and short addresses
// Turnout and accessory states (thrown/closed = 0/1 or 1/0) can be set to match RCN-213
// Bugfix: one-off error in CIPSEND drop
// Bugfix: disgnostic display of ack pulses >32kus
// Bugfix: diagnostic display of ack pulses >32kus
// Bugfix: Current read from wrong ADC during interrupt
// 3.2.0 Development Release Includes all of 3.1.1 thru 3.1.7 enhancements
// 3.1.7 Bugfix: Unknown locos should have speed forward