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

Compare commits

...

96 Commits

Author SHA1 Message Date
pmantoine
3868bb19ac More uint type fixes 2023-04-08 14:51:10 +08:00
pmantoine
7589917638 STM32 ADCee fix 2023-04-08 14:15:38 +08:00
Harald Barth
0d82370380 devel date 2023-04-07 20:46:20 +02:00
Harald Barth
ff6034dff2 curl only needed when downloading 2023-04-07 20:45:21 +02:00
Harald Barth
5d0de6b807 platformio wants this 2023-04-07 20:44:40 +02:00
pmantoine
c3d2e5b222 Fix to PIO build target names for Teensy 2023-04-07 13:59:49 +10:00
Asbelos
273f55b143 4.2.41 Hal setup and DNOU8 fix 2023-04-05 23:19:43 +01:00
peteGSX
86cb8f4666 Merge pull request #327 from DCC-EX:auto-disable-default-i2c
Added disable logic
2023-04-06 07:09:32 +10:00
peteGSX
9571088e1b Added disable logic 2023-04-06 07:03:59 +10:00
Neil McKechnie
1b4faa92cd Update IO_DFPlayer.h
Reinstate STOP command in place of PAUSE, as PAUSE was being reported differently to STOP in the status response.
2023-03-31 17:58:30 +01:00
Neil McKechnie
6fbaca7930 Update IO_DFPlayer.h
Ensure device goes off-line when not responding.
2023-03-31 16:50:18 +01:00
Neil McKechnie
6b535654f8 DFplayer driver now polls device to detect failures and errors.
Add cyclic (1-second) poll of DFplayer device to detect if it goes unresponsive.
2023-03-31 16:40:40 +01:00
peteGSX
2c943d250e Merge pull request #326 from DCC-EX:287-to-do-clean-up-rotary-encoder-device-driver-compile-time-warning
Cleaned up warning
2023-03-30 07:01:40 +10:00
peteGSX
89664eff9d Cleaned up warning 2023-03-30 06:54:18 +10:00
f8b054cf6a [ESP32] Use GPIO 35/A2 and 34/A3 for current sensing (#325)
* [ESP32] Use GPIO 35/A2 and 34/A3 for current sensing while used in combination with the standard Motor Shield
* Update version.h changelog
2023-03-27 10:44:47 -04:00
Neil McKechnie
d2a8aebd0f Merge branch 'devel' of https://github.com/DCC-EX/CommandStation-EX into devel 2023-03-27 13:08:19 +01:00
Neil McKechnie
86c3020672 Correct display of high VPIN numbers in diagnostic output.
No functional change.
VPINs are unsigned integers in the range 0-65535 (although the highest values are special, 65535=VPIN_NONE).  Values above 32767 were erroneously being displayed as negative.  This has been fixed, which is a pre-requisite for allowing VPINs above 32767 to be used.
2023-03-27 13:08:14 +01:00
Neil McKechnie
60ea7f081a Correct display of high VPIN numbers in diagnostic output.
No functional change.
VPINs are unsigned integers in the range 0-65535 (although the highest values are special, 65535=VPIN_NONE).  Values above 32767 were erroneously being displayed as negative.  This has been fixed, which is a pre-requisite for allowing VPINs above 32767 to be used.
2023-03-27 13:03:19 +01:00
Neil McKechnie
f348857ddb Add FLAGS device for EX-RAIL state communications. Improve VPIN display in messages.
FLAGS HAL device added to IODevice.h, which allows use of SET/RESET/<Z>/<T> to set and reset a VPIN state, and to allow <S>/IF/IFNOT/AT/WAITFOR/etc. to monitor the VPIN state.
Also, correct handling of VPINs above 32767 in DIAG calls within IODevice.cpp and IODevice.h.
2023-03-27 12:39:11 +01:00
Harald Barth
bdd4bc9999 version 2023-03-25 22:26:57 +01:00
Harald Barth
8a425fe0ef do not broadcast a turnout state that has not changed 2 2023-03-25 19:28:37 +01:00
Harald Barth
1ec378281b do not broadcast a turnout state that has not changed 2023-03-25 12:14:58 +01:00
Asbelos
51a480dff3 doc typo only 2023-03-24 00:24:03 +00:00
Asbelos
f0ee8aeb85 z Commands 2023-03-23 19:52:49 +00:00
peteGSX
94d0aa92d9 Merge pull request #324 from DCC-EX:fix-analogue-input-bug
Fix-analogue-input-bug
2023-03-21 07:09:52 +10:00
peteGSX
82c447e8a4 Merge branch 'fix-analogue-input-bug' of https://github.com/DCC-EX/CommandStation-EX into fix-analogue-input-bug 2023-03-21 07:04:19 +10:00
peteGSX
a3d03ac68c Fix validated, update version 2023-03-21 07:04:08 +10:00
peteGSX
b183439a5b Using correct size for memcpy 2023-03-21 07:03:23 +10:00
Harald Barth
d51281f1f2 github tag 2023-03-20 21:24:42 +01:00
Harald Barth
168368864c Merge branch 'devel' of https://github.com/DCC-EX/CommandStation-EX into devel 2023-03-20 21:23:02 +01:00
Harald Barth
a75ca00e3c exchange pin number to track letter part 2 2023-03-20 21:22:48 +01:00
peteGSX
7ab5f556d9 Using correct size for memcpy 2023-03-21 05:30:33 +10:00
peteGSX
337bd969a1 Merge pull request #323 from DCC-EX:ex-io-analogue-input-bug
Fixed non-working analogue inputs
2023-03-20 19:11:59 +10:00
Harald Barth
21c99c8694 improve Wifi connect messages 2023-03-20 10:11:14 +01:00
peteGSX
4087cd6e29 Fixed non-working analogue inputs 2023-03-20 19:05:53 +10:00
Harald Barth
2fb485847f exchange pin number to track letter 2023-03-20 10:03:02 +01:00
Neil McKechnie
43c7baf8f5 Fix display scrolling on LCD and OLED
Eliminate spurious blanking of screen in mode 1, duplicated lines of text in mode 2, and non-display of more than the first screen-full of lines in mode 0.
2023-03-19 22:06:02 +00:00
Neil McKechnie
2e1a2d38e3 Update IO_EXIOExpander.h
Reinstate byte-wise processing of analogue input values.
2023-03-19 01:20:20 +00:00
Asbelos
fe18341994 Update myAutomation.example.h
better example with power on
2023-03-18 18:53:48 +00:00
Asbelos
329dc41452 Remove implicit AUTOSTART 2023-03-18 18:52:01 +00:00
Neil McKechnie
c4b4e11a67 Update IO_EXIOExpander.h
Avoid repeated error messages for a single fault.
2023-03-18 15:30:14 +00:00
Neil McKechnie
e55dc51bdb EX-IOExpander updates 2023-03-18 15:05:21 +00:00
Neil McKechnie
5dd2770442 Update IO_HCSR04.h
Modify mode of measurement so that the driver doesn't loop for long periods waiting for the incoming pulse to complete.   Original loop behaviour can be reinstated by adding LOOP option in create call (see comment header in file).
2023-03-17 21:15:26 +00:00
Neil McKechnie
d67b07fe46 Merge branch 'devel' of https://github.com/DCC-EX/CommandStation-EX into devel 2023-03-15 18:10:30 +00:00
Neil McKechnie
3073061596 Update IO_DFPlayer.h
Bugfix, volume not working correctly.
2023-03-15 18:10:27 +00:00
Harald Barth
278347756a Bugfix Scroll LCD without empty lines and consistent 2023-03-15 16:41:02 +01:00
Neil McKechnie
3d35e78533 Update version.h 2023-03-15 09:39:30 +00:00
Neil McKechnie
75b5806eb7 Shorten I2C error message 2023-03-15 09:39:20 +00:00
Neil McKechnie
4a1210fa64 Remove HA mode from STM32
In some pin configurations for DC track mode, the use of analogWrite will conflict with other timer uses including HA mode.
 Consequently, the HA mode support has been temporarily removed pending a suitable solution for this.  Original use of Timer11 has been reinstated.
2023-03-15 09:31:54 +00:00
Neil McKechnie
72c76391a5 Merge branch 'devel' of https://github.com/DCC-EX/CommandStation-EX into devel 2023-03-15 09:21:24 +00:00
Neil McKechnie
325d4bce73 Update IO_DFPlayer.h
Rework delay between command: instead of sending null characters, which doesn't work on some chip sets, send commands from the _loop() function with a 100ms delay between consecutive commands.
2023-03-15 09:20:42 +00:00
Harald Barth
27ba551986 Bugfix LCD showed random characters in SCROLLMODE 2 2023-03-14 20:50:24 +01:00
peteGSX
ce12f3b6c5 Merge pull request #320 from DCC-EX:ex-io-driver-updates
Ex-io-driver-updates
2023-03-14 19:10:23 +10:00
peteGSX
48cd567bda Update version after testing 2023-03-14 19:04:08 +10:00
peteGSX
25676aab6b Update comments 2023-03-14 07:32:08 +10:00
peteGSX
42bddb587e Update .gitignore 2023-03-14 07:25:30 +10:00
peteGSX
a51cefbdeb Delete settings.json 2023-03-14 07:23:55 +10:00
peteGSX
5fc925bfc6 Delete extensions.json 2023-03-14 07:23:42 +10:00
peteGSX
ca2e5e6ce3 Undo vscode change 2023-03-14 07:21:55 +10:00
peteGSX
9728e15e0a Merge branch 'ex-io-driver-updates' of https://github.com/DCC-EX/CommandStation-EX into ex-io-driver-updates 2023-03-14 07:20:46 +10:00
peteGSX
c83741d2b4 Add read refresh delays 2023-03-14 07:20:27 +10:00
peteGSX
df3eb11eb9 Add read refresh delays 2023-03-14 07:19:20 +10:00
Asbelos
d89dd0d1fa command ref work in progress 2023-03-13 00:53:42 +00:00
peteGSX
95d0120204 Implement status checks 2023-03-13 08:38:28 +10:00
peteGSX
0cc07ed1df Starting on driver feedback 2023-03-13 05:29:22 +10:00
Asbelos
5e60fb4e27 SAMD21 odd byte boundary 2023-03-11 22:46:11 +00:00
Harald Barth
881463ada9 Merge branch 'devel' of https://github.com/DCC-EX/CommandStation-EX into devel 2023-03-10 17:52:16 +01:00
Harald Barth
45cf610028 Bugfix Ethernet shield: Static IP now possible 2023-03-10 17:49:51 +01:00
Neil McKechnie
471b8ac8e1 Update I2CManager.cpp
Rearrange I2C short-circuit check to before I2C is initialised.
2023-03-09 16:28:07 +00:00
Neil McKechnie
3ae1859ec7 Merge branch 'devel' of https://github.com/DCC-EX/CommandStation-EX into devel 2023-03-09 16:01:10 +00:00
Neil McKechnie
679e5885c4 Update IO_HALDisplay.h
Enable I2C address overlap check on HAL display.
2023-03-09 15:59:52 +00:00
Neil McKechnie
59c6c1e5af Update examples and comments. 2023-03-09 15:59:25 +00:00
Harald Barth
f94a5f971e Bugfix signalpin2 was not set up in shadow port 2023-03-07 16:20:00 +01:00
Asbelos
1d29436008 Compiler pedantics 2023-03-06 13:47:59 +00:00
Asbelos
bec8aea5a5 TM Broadcasts
TM changes will trigger TM state broadcasts
2023-03-06 11:57:14 +00:00
peteGSX
4f23dbc984 Merge pull request #315 from DCC-EX:47-to-do-update-device-driver-to-use-non-blocking-i2c
Non-blocking implemented
2023-03-04 19:02:11 +10:00
peteGSX
46070e2999 Non-blocking implemented 2023-03-04 18:55:13 +10:00
Neil McKechnie
22c0bff697 Merge branch 'devel' of https://github.com/DCC-EX/CommandStation-EX into devel 2023-03-02 23:01:47 +00:00
Neil McKechnie
19bbb186e7 Create IO_TouchKeypad.h
Driver for 16-pad capacitative key pad device (TTP229-B based).
2023-03-02 23:01:44 +00:00
Asbelos
a17a55d904 Implement <JG> <JI> 2023-03-02 13:03:05 +00:00
Asbelos
b969563d35 Squashed commit of the following:
commit 4d8efcdd05
Author: Asbelos <asbelos@btinternet.com>
Date:   Wed Mar 1 16:32:05 2023 +0000

    Reinstate obsolete <s>

commit 003313998b
Author: Asbelos <asbelos@btinternet.com>
Date:   Wed Mar 1 16:07:11 2023 +0000

    Change <I><G> to <JI><JG>

commit c72bf51959
Author: Asbelos <asbelos@btinternet.com>
Date:   Sat Feb 25 17:38:39 2023 +0000

    G and I commands
2023-03-02 12:56:30 +00:00
Asbelos
f0c1ea958c 4.2.19 sensorOffset bugfix 2023-03-02 10:45:39 +00:00
Neil McKechnie
ca4592dc3e Reinstate original #ifdef DIAG_IO tests in servo modules 2023-03-01 23:09:27 +00:00
Neil McKechnie
0663cc6138 Update IO_EXIOExpander.h
_I2CAddress or _i2cAddress - the checkOverlap function uses the former, and the driver uses the latter.  I incorrectly used the wrong one!
2023-02-28 23:49:51 +00:00
Neil McKechnie
5fb10fa6d0 Delete IO_ExternalEEPROM.h 2023-02-28 20:09:37 +00:00
Harald Barth
1d47dce473 update tag 2023-02-28 15:22:57 +01:00
Harald Barth
8a126906f3 Only need do anything if cab existed 2023-02-28 15:20:29 +01:00
Harald Barth
b01e4388ce Small typo in tone scale 2023-02-28 15:17:04 +01:00
Colin Murdoch
4adcdc1b0b Update config.example.h
Removed redundant define for FastClock no longer required.
2023-02-28 12:12:08 +00:00
Neil McKechnie
95b640686a Merge branch 'devel' of https://github.com/DCC-EX/CommandStation-EX into devel 2023-02-25 11:43:39 +00:00
Neil McKechnie
f56f5d9ebe Update I2CManager_Wire.h
Add alternative multiplexer support for I2C Wire subsystem.
2023-02-25 11:43:36 +00:00
Neil McKechnie
8c8a913678 Update IO_HALDisplay.h
Check for memory allocation errors.
2023-02-25 11:43:05 +00:00
Neil McKechnie
711ad6f030 Update SSD1306Ascii.cpp
Add remaining extended graphics characters (still no international characters though.
2023-02-25 11:42:43 +00:00
Neil McKechnie
c2983efebb Update to comments 2023-02-25 11:42:12 +00:00
Asbelos
02ee8ad080 Removed duplicate DIAG 2023-02-24 16:56:21 +00:00
Neil McKechnie
780c6ea162 Revert "Update DisplayInterface.cpp"
This reverts commit a23f5839b7.
2023-02-24 09:39:00 +00:00
55 changed files with 2201 additions and 778 deletions

8
.gitignore vendored
View File

@@ -7,15 +7,9 @@ Release/*
.pio/ .pio/
.vscode/ .vscode/
config.h config.h
.vscode/*
# mySetup.h
mySetup.cpp mySetup.cpp
myHal.cpp myHal.cpp
# myAutomation.h
myFilter.cpp myFilter.cpp
# myAutomation.h
# myLayout.h
my*.h my*.h
!my*.example.h !my*.example.h
.vscode/extensions.json compile_commands.json
.vscode/extensions.json

View File

@@ -1,10 +0,0 @@
{
// See http://go.microsoft.com/fwlink/?LinkId=827846
// for the documentation about the extensions.json format
"recommendations": [
"platformio.platformio-ide"
],
"unwantedRecommendations": [
"ms-vscode.cpptools-extension-pack"
]
}

12
.vscode/settings.json vendored
View File

@@ -1,12 +0,0 @@
{
"files.associations": {
"array": "cpp",
"deque": "cpp",
"string": "cpp",
"unordered_map": "cpp",
"vector": "cpp",
"string_view": "cpp",
"initializer_list": "cpp",
"cstdint": "cpp"
}
}

View File

@@ -179,10 +179,7 @@ void CommandDistributor::setClockTime(int16_t clocktime, int8_t clockrate, byte
{ {
case 1: case 1:
if (clocktime != lastclocktime){ if (clocktime != lastclocktime){
if (Diag::CMD) { // CAH. DIAG removed because LCD does it anyway.
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); LCD(6,F("Clk Time:%d Sp %d"), clocktime, clockrate);
// look for an event for this time // look for an event for this time
RMFT2::clockEvent(clocktime,1); RMFT2::clockEvent(clocktime,1);
@@ -236,3 +233,7 @@ void CommandDistributor::broadcastText(const FSH * msg) {
broadcastReply(WITHROTTLE_TYPE, F("Hm%S\n"), msg); broadcastReply(WITHROTTLE_TYPE, F("Hm%S\n"), msg);
#endif #endif
} }
void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr) {
broadcastReply(COMMAND_TYPE, format,trackLetter,dcAddr);
}

View File

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

View File

@@ -75,6 +75,9 @@ void setup()
DIAG(F("License GPLv3 fsf.org (c) dcc-ex.com")); DIAG(F("License GPLv3 fsf.org (c) dcc-ex.com"));
// Initialise HAL layer before reading EEprom or setting up MotorDrivers
IODevice::begin();
DISPLAY_START ( DISPLAY_START (
// This block is still executed for DIAGS if display not in use // This block is still executed for DIAGS if display not in use
LCD(0,F("DCC-EX v%S"),F(VERSION)); LCD(0,F("DCC-EX v%S"),F(VERSION));
@@ -96,10 +99,7 @@ void setup()
#if ETHERNET_ON #if ETHERNET_ON
EthernetInterface::setup(); EthernetInterface::setup();
#endif // ETHERNET_ON #endif // ETHERNET_ON
// 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, // 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! // let's make sure to initialise the ADCee class!
ADCee::begin(); ADCee::begin();

View File

@@ -576,9 +576,11 @@ void DCC::setLocoId(int id,ACK_CALLBACK callback) {
void DCC::forgetLoco(int cab) { // removes any speed reminders for this loco void DCC::forgetLoco(int cab) { // removes any speed reminders for this loco
setThrottle2(cab,1); // ESTOP this loco if still on track setThrottle2(cab,1); // ESTOP this loco if still on track
int reg=lookupSpeedTable(cab); int reg=lookupSpeedTable(cab, false);
if (reg>=0) speedTable[reg].loco=0; if (reg>=0) {
setThrottle2(cab,1); // ESTOP if this loco still on track speedTable[reg].loco=0;
setThrottle2(cab,1); // ESTOP if this loco still on track
}
} }
void DCC::forgetAllLocos() { // removes all speed reminders void DCC::forgetAllLocos() { // removes all speed reminders
setThrottle2(0,1); // ESTOP all locos still on track setThrottle2(0,1); // ESTOP all locos still on track

View File

@@ -79,6 +79,8 @@ const int16_t HASH_KEYWORD_TT=2688;
const int16_t HASH_KEYWORD_VPIN=-415; const int16_t HASH_KEYWORD_VPIN=-415;
const int16_t HASH_KEYWORD_A='A'; const int16_t HASH_KEYWORD_A='A';
const int16_t HASH_KEYWORD_C='C'; const int16_t HASH_KEYWORD_C='C';
const int16_t HASH_KEYWORD_G='G';
const int16_t HASH_KEYWORD_I='I';
const int16_t HASH_KEYWORD_R='R'; const int16_t HASH_KEYWORD_R='R';
const int16_t HASH_KEYWORD_T='T'; const int16_t HASH_KEYWORD_T='T';
const int16_t HASH_KEYWORD_X='X'; const int16_t HASH_KEYWORD_X='X';
@@ -342,6 +344,20 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
return; return;
break; break;
case 'z': // direct pin manipulation
if (p[0]==0) break;
if (params==1) { // <z vpin | -vpin>
if (p[0]>0) IODevice::write(p[0],HIGH);
else IODevice::write(-p[0],LOW);
return;
}
if (params>=2 && params<=4) { // <z vpin ana;og profile duration>
// unused params default to 0
IODevice::writeAnalogue(p[0],p[1],p[2],p[3]);
return;
}
break;
case 'Z': // OUTPUT <Z ...> case 'Z': // OUTPUT <Z ...>
if (parseZ(stream, params, p)) if (parseZ(stream, params, p))
return; return;
@@ -501,8 +517,10 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
return; return;
case 'c': // SEND METER RESPONSES <c> case 'c': // SEND METER RESPONSES <c>
// No longer supported because of multiple tracks <c MeterName value C/V unit min max res warn> // No longer useful because of multiple tracks See <JG> and <JI>
break; if (params>0) break;
TrackManager::reportObsoleteCurrent(stream);
return;
case 'Q': // SENSORS <Q> case 'Q': // SENSORS <Q>
Sensor::printAll(stream); Sensor::printAll(stream);
@@ -512,9 +530,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
StringFormatter::send(stream, F("<iDCC-EX V-%S / %S / %S G-%S>\n"), F(VERSION), F(ARDUINO_TYPE), DCC::getMotorShieldName(), F(GITHUB_SHA)); 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 CommandDistributor::broadcastPower(); // <s> is the only "get power status" command we have
Turnout::printAll(stream); //send all Turnout states Turnout::printAll(stream); //send all Turnout states
Output::printAll(stream); //send all Output states
Sensor::printAll(stream); //send all Sensor states Sensor::printAll(stream); //send all Sensor states
// TODO Send stats of speed reminders table
return; return;
#ifndef DISABLE_EEPROM #ifndef DISABLE_EEPROM
@@ -583,6 +599,16 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
} }
CommandDistributor::setClockTime(p[1], p[2], 1); CommandDistributor::setClockTime(p[1], p[2], 1);
return; return;
case HASH_KEYWORD_G: // <JG> current gauge limits
if (params>1) break;
TrackManager::reportGauges(stream); // <g limit...limit>
return;
case HASH_KEYWORD_I: // <JI> current values
if (params>1) break;
TrackManager::reportCurrent(stream); // <g limit...limit>
return;
case HASH_KEYWORD_A: // <JA> returns automations/routes case HASH_KEYWORD_A: // <JA> returns automations/routes
StringFormatter::send(stream, F("<jA")); StringFormatter::send(stream, F("<jA"));
@@ -941,7 +967,7 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
break; break;
case HASH_KEYWORD_ANIN: // <D ANIN vpin> Display analogue input value case HASH_KEYWORD_ANIN: // <D ANIN vpin> Display analogue input value
DIAG(F("VPIN=%d value=%d"), p[1], IODevice::readAnalogue(p[1])); DIAG(F("VPIN=%u value=%d"), p[1], IODevice::readAnalogue(p[1]));
break; break;
#if !defined(IO_NO_HAL) #if !defined(IO_NO_HAL)

View File

@@ -162,7 +162,7 @@ uint16_t ADCee::usedpins = 0;
int * ADCee::analogvals = NULL; int * ADCee::analogvals = NULL;
int ADCee::init(uint8_t pin) { int ADCee::init(uint8_t pin) {
uint id = pin - A0; uint8_t id = pin - A0;
int value = 0; int value = 0;
if (id > NUM_ADC_INPUTS) if (id > NUM_ADC_INPUTS)
@@ -210,7 +210,7 @@ int ADCee::read(uint8_t pin, bool fromISR) {
#pragma GCC push_options #pragma GCC push_options
#pragma GCC optimize ("-O3") #pragma GCC optimize ("-O3")
void ADCee::scan() { void ADCee::scan() {
static uint id = 0; // id and mask are the same thing but it is faster to static uint8_t 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 uint16_t mask = 1; // increment and shift instead to calculate mask from id
static bool waiting = false; static bool waiting = false;

View File

@@ -40,7 +40,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 HardwareSerial Serial6(PA12, PA11); // Rx=PA12, Tx=PA11 -- CN10 pins 12 and 14 - F411RE
#elif defined(ARDUINO_NUCLEO_F446RE) #elif defined(ARDUINO_NUCLEO_F446RE)
// Nucleo-64 boards don't have Serial1 defined by default // Nucleo-64 boards don't have Serial1 defined by default
HardwareSerial Serial1(PA10, PB6); // Rx=PA10, Tx=PB6 -- CN10 pins 33 and 17 - F446RE 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 // 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. // 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) #elif defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)
@@ -50,17 +50,106 @@ HardwareSerial Serial1(PG9, PG14); // Rx=PG9, Tx=PG14 -- D0, D1 - F412ZG/F446ZE
#warning Serial1 not defined #warning Serial1 not defined
#endif #endif
///////////////////////////////////////////////////////////////////////////////////////////////
// Experimental code for High Accuracy (HA) DCC Signal mode
// Warning - use of TIM2 and TIM3 can affect the use of analogWrite() function on certain pins,
// which is used by the DC motor types.
///////////////////////////////////////////////////////////////////////////////////////////////
// INTERRUPT_CALLBACK interruptHandler=0;
// // Let's use STM32's timer #2 which supports hardware pulse generation on pin D13.
// // Also, timer #3 will do hardware pulses on pin D12. This gives
// // accurate timing, independent of the latency of interrupt handling.
// // We only need to interrupt on one of these (TIM2), the other will just generate
// // pulses.
// HardwareTimer timer(TIM2);
// HardwareTimer timerAux(TIM3);
// static bool tim2ModeHA = false;
// static bool tim3ModeHA = false;
// // Timer IRQ handler
// void Timer_Handler() {
// interruptHandler();
// }
// void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
// interruptHandler=callback;
// noInterrupts();
// // adc_set_sample_rate(ADC_SAMPLETIME_480CYCLES);
// timer.pause();
// timerAux.pause();
// timer.setPrescaleFactor(1);
// timer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT);
// timer.attachInterrupt(Timer_Handler);
// timer.refresh();
// timerAux.setPrescaleFactor(1);
// timerAux.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT);
// timerAux.refresh();
// timer.resume();
// timerAux.resume();
// interrupts();
// }
// bool DCCTimer::isPWMPin(byte pin) {
// // Timer 2 Channel 1 controls pin D13, and Timer3 Channel 1 controls D12.
// // Enable the appropriate timer channel.
// switch (pin) {
// case 12:
// return true;
// case 13:
// return true;
// default:
// return false;
// }
// }
// void DCCTimer::setPWM(byte pin, bool high) {
// // Set the timer so that, at the next counter overflow, the requested
// // pin state is activated automatically before the interrupt code runs.
// // TIM2 is timer, TIM3 is timerAux.
// switch (pin) {
// case 12:
// if (!tim3ModeHA) {
// timerAux.setMode(1, TIMER_OUTPUT_COMPARE_INACTIVE, D12);
// tim3ModeHA = true;
// }
// if (high)
// TIM3->CCMR1 = (TIM3->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_0;
// else
// TIM3->CCMR1 = (TIM3->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_1;
// break;
// case 13:
// if (!tim2ModeHA) {
// timer.setMode(1, TIMER_OUTPUT_COMPARE_INACTIVE, D13);
// tim2ModeHA = true;
// }
// if (high)
// TIM2->CCMR1 = (TIM2->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_0;
// else
// TIM2->CCMR1 = (TIM2->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_1;
// break;
// }
// }
// void DCCTimer::clearPWM() {
// timer.setMode(1, TIMER_OUTPUT_COMPARE_INACTIVE, NC);
// tim2ModeHA = false;
// timerAux.setMode(1, TIMER_OUTPUT_COMPARE_INACTIVE, NC);
// tim3ModeHA = false;
// }
///////////////////////////////////////////////////////////////////////////////////////////////
INTERRUPT_CALLBACK interruptHandler=0; INTERRUPT_CALLBACK interruptHandler=0;
// Let's use STM32's timer #2 which supports hardware pulse generation on pin D13. // Let's use STM32's timer #11 until disabused of this notion
// Also, timer #3 will do hardware pulses on pin D12. This gives // Timer #11 is used for "servo" library, but as DCC-EX is not using
// accurate timing, independent of the latency of interrupt handling. // this libary, we should be free and clear.
// We only need to interrupt on one of these (TIM2), the other will just generate HardwareTimer timer(TIM11);
// pulses.
HardwareTimer timer(TIM2);
HardwareTimer timerAux(TIM3);
// Timer IRQ handler // Timer IRQ handler
void Timer_Handler() { void Timer11_Handler() {
interruptHandler(); interruptHandler();
} }
@@ -70,59 +159,31 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
// adc_set_sample_rate(ADC_SAMPLETIME_480CYCLES); // adc_set_sample_rate(ADC_SAMPLETIME_480CYCLES);
timer.pause(); timer.pause();
timerAux.pause();
timer.setPrescaleFactor(1); timer.setPrescaleFactor(1);
// timer.setOverflow(CLOCK_CYCLES * 2);
timer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT); timer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT);
timer.attachInterrupt(Timer_Handler); timer.attachInterrupt(Timer11_Handler);
timer.refresh(); timer.refresh();
timerAux.setPrescaleFactor(1);
timerAux.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT);
timerAux.refresh();
timer.resume(); timer.resume();
timerAux.resume();
interrupts(); interrupts();
} }
bool DCCTimer::isPWMPin(byte pin) { bool DCCTimer::isPWMPin(byte pin) {
// Timer 2 Channel 1 controls pin D13, and Timer3 Channel 1 controls D12. //TODO: SAMD whilst this call to digitalPinHasPWM will reveal which pins can do PWM,
// Enable the appropriate timer channel. // there's no support yet for High Accuracy, so for now return false
switch (pin) { // return digitalPinHasPWM(pin);
case 12: return false;
timerAux.setMode(1, TIMER_OUTPUT_COMPARE_INACTIVE, D12);
return true;
case 13:
timer.setMode(1, TIMER_OUTPUT_COMPARE_INACTIVE, D13);
return true;
default:
return false;
}
} }
void DCCTimer::setPWM(byte pin, bool high) { void DCCTimer::setPWM(byte pin, bool high) {
// Set the timer so that, at the next counter overflow, the requested // TODO: High Accuracy mode is not supported as yet, and may never need to be
// pin state is activated automatically before the interrupt code runs. (void) pin;
// TIM2 is timer, TIM3 is timerAux. (void) high;
switch (pin) {
case 12:
if (high)
TIM3->CCMR1 = (TIM3->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_0;
else
TIM3->CCMR1 = (TIM3->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_1;
break;
case 13:
if (high)
TIM2->CCMR1 = (TIM2->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_0;
else
TIM2->CCMR1 = (TIM2->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_1;
break;
}
} }
void DCCTimer::clearPWM() { void DCCTimer::clearPWM() {
timer.setMode(1, TIMER_OUTPUT_COMPARE_INACTIVE, NC); return;
timerAux.setMode(1, TIMER_OUTPUT_COMPARE_INACTIVE, NC);
} }
void DCCTimer::getSimulatedMacAddress(byte mac[6]) { void DCCTimer::getSimulatedMacAddress(byte mac[6]) {
@@ -176,7 +237,7 @@ int16_t ADCee::ADCmax() {
} }
int ADCee::init(uint8_t pin) { int ADCee::init(uint8_t pin) {
uint id = pin - A0; uint8_t id = pin - A0;
int value = 0; int value = 0;
PinName stmpin = digitalPin[analogInputPin[id]]; PinName stmpin = digitalPin[analogInputPin[id]];
uint32_t stmgpio = stmpin / 16; // 16-bits per GPIO port group on STM32 uint32_t stmgpio = stmpin / 16; // 16-bits per GPIO port group on STM32
@@ -245,7 +306,7 @@ int ADCee::read(uint8_t pin, bool fromISR) {
#pragma GCC push_options #pragma GCC push_options
#pragma GCC optimize ("-O3") #pragma GCC optimize ("-O3")
void ADCee::scan() { void ADCee::scan() {
static uint id = 0; // id and mask are the same thing but it is faster to static uint8_t 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 uint16_t mask = 1; // increment and shift instead to calculate mask from id
static bool waiting = false; static bool waiting = false;

View File

@@ -36,7 +36,7 @@
* not held up significantly. The exception to this is when * not held up significantly. The exception to this is when
* the loop2() function is called with force=true, where * the loop2() function is called with force=true, where
* a screen update is executed to completion. This is normally * a screen update is executed to completion. This is normally
* only noMoreRowsToDisplay during start-up. * only done during start-up.
* The scroll mode is selected by defining SCROLLMODE as 0, 1 or 2 * The scroll mode is selected by defining SCROLLMODE as 0, 1 or 2
* in the config.h. * in the config.h.
* #define SCROLLMODE 0 is scroll continuous (fill screen if poss), * #define SCROLLMODE 0 is scroll continuous (fill screen if poss),
@@ -51,11 +51,10 @@
Display::Display(DisplayDevice *deviceDriver) { Display::Display(DisplayDevice *deviceDriver) {
_deviceDriver = deviceDriver; _deviceDriver = deviceDriver;
// Get device dimensions in characters (e.g. 16x2). // Get device dimensions in characters (e.g. 16x2).
numCharacterColumns = _deviceDriver->getNumCols(); numScreenColumns = _deviceDriver->getNumCols();
numCharacterRows = _deviceDriver->getNumRows();; numScreenRows = _deviceDriver->getNumRows();
for (uint8_t row = 0; row < MAX_CHARACTER_ROWS; row++) for (uint8_t row = 0; row < MAX_CHARACTER_ROWS; row++)
rowBuffer[row][0] = '\0'; rowBuffer[row][0] = '\0';
topRow = ROW_INITIAL; // loop2 will fill from row 0
addDisplay(0); // Add this display as display number 0 addDisplay(0); // Add this display as display number 0
}; };
@@ -69,20 +68,19 @@ void Display::_clear() {
_deviceDriver->clearNative(); _deviceDriver->clearNative();
for (uint8_t row = 0; row < MAX_CHARACTER_ROWS; row++) for (uint8_t row = 0; row < MAX_CHARACTER_ROWS; row++)
rowBuffer[row][0] = '\0'; rowBuffer[row][0] = '\0';
topRow = ROW_INITIAL; // loop2 will fill from row 0
} }
void Display::_setRow(uint8_t line) { void Display::_setRow(uint8_t line) {
hotRow = line; hotRow = line;
hotCol = 0; hotCol = 0;
rowBuffer[hotRow][0] = 0; // Clear existing text rowBuffer[hotRow][0] = '\0'; // Clear existing text
} }
size_t Display::_write(uint8_t b) { size_t Display::_write(uint8_t b) {
if (hotRow >= MAX_CHARACTER_ROWS || hotCol >= MAX_CHARACTER_COLS) return -1; if (hotRow >= MAX_CHARACTER_ROWS || hotCol >= MAX_CHARACTER_COLS) return -1;
rowBuffer[hotRow][hotCol] = b; rowBuffer[hotRow][hotCol] = b;
hotCol++; hotCol++;
rowBuffer[hotRow][hotCol] = 0; rowBuffer[hotRow][hotCol] = '\0';
return 1; return 1;
} }
@@ -109,8 +107,8 @@ Display *Display::loop2(bool force) {
return NULL; return NULL;
} else { } else {
// force full screen update from the beginning. // force full screen update from the beginning.
rowFirst = ROW_INITIAL; rowFirst = 0;
rowNext = ROW_INITIAL; rowCurrent = 0;
bufferPointer = 0; bufferPointer = 0;
noMoreRowsToDisplay = false; noMoreRowsToDisplay = false;
slot = 0; slot = 0;
@@ -118,15 +116,20 @@ Display *Display::loop2(bool force) {
do { do {
if (bufferPointer == 0) { if (bufferPointer == 0) {
// Find a line of data to write to the screen. // Search for non-blank row
if (rowFirst == ROW_INITIAL) rowFirst = rowNext; while (!noMoreRowsToDisplay) {
if (findNextNonBlankRow()) { if (!isCurrentRowBlank()) break;
moveToNextRow();
if (rowCurrent == rowFirst) noMoreRowsToDisplay = true;
}
if (noMoreRowsToDisplay) {
// No non-blank lines left, so draw blank line
buffer[0] = '\0';
} else {
// Non-blank line found, so copy it (including terminator) // Non-blank line found, so copy it (including terminator)
for (uint8_t i = 0; i <= MAX_CHARACTER_COLS; i++) for (uint8_t i = 0; i <= MAX_CHARACTER_COLS; i++)
buffer[i] = rowBuffer[rowNext][i]; buffer[i] = rowBuffer[rowCurrent][i];
} else {
// No non-blank lines left, so draw a blank line
buffer[0] = 0;
} }
_deviceDriver->setRowNative(slot); // Set position for display _deviceDriver->setRowNative(slot); // Set position for display
charIndex = 0; charIndex = 0;
@@ -142,21 +145,49 @@ Display *Display::loop2(bool force) {
} }
if (++charIndex >= MAX_CHARACTER_COLS) { if (++charIndex >= MAX_CHARACTER_COLS) {
// Screen slot completed, move to next slot on screen // Screen slot completed, move to next nonblank row
bufferPointer = 0; bufferPointer = 0;
for (;;) {
moveToNextRow();
if (rowCurrent == rowFirst) {
noMoreRowsToDisplay = true;
break;
}
if (!isCurrentRowBlank()) break;
}
// Move to next screen slot, if available
slot++; slot++;
if (slot >= numCharacterRows) { if (slot >= numScreenRows) {
// Last slot on screen written, reset ready for next screen update. // Last slot on screen written, so get ready for next screen update.
#if SCROLLMODE==2 #if SCROLLMODE==0
if (!noMoreRowsToDisplay) { // Scrollmode 0 scrolls continuously. If the rows fit on the screen,
// On next refresh, restart one row on from previous start. // then restart at row 0, but otherwise continue with the row
rowNext = rowFirst; // after the last one displayed.
findNextNonBlankRow(); if (countNonBlankRows() <= numScreenRows)
rowCurrent = 0;
rowFirst = rowCurrent;
#elif SCROLLMODE==1
// Scrollmode 1 scrolls by page, so if the last page has just completed then
// next time restart with row 0.
if (noMoreRowsToDisplay)
rowFirst = rowCurrent = 0;
#else
// Scrollmode 2 scrolls by row. If the rows don't fit on the screen,
// then start one row further on next time. If they do fit, then
// show them in order and start next page at row 0.
if (countNonBlankRows() <= numScreenRows) {
rowFirst = rowCurrent = 0;
} else {
// Find first non-blank row after the previous first row
rowCurrent = rowFirst;
do {
moveToNextRow();
} while (isCurrentRowBlank());
rowFirst = rowCurrent;
} }
#endif #endif
noMoreRowsToDisplay = false; noMoreRowsToDisplay = false;
slot = 0; slot = 0;
rowFirst = ROW_INITIAL;
lastScrollTime = currentMillis; lastScrollTime = currentMillis;
return NULL; return NULL;
} }
@@ -167,30 +198,22 @@ Display *Display::loop2(bool force) {
return NULL; return NULL;
} }
bool Display::findNextNonBlankRow() { bool Display::isCurrentRowBlank() {
while (!noMoreRowsToDisplay) { return (rowBuffer[rowCurrent][0] == '\0');
if (rowNext == ROW_INITIAL) }
rowNext = 0;
else void Display::moveToNextRow() {
rowNext = rowNext + 1; // Skip blank rows
if (rowNext >= MAX_CHARACTER_ROWS) rowNext = ROW_INITIAL; if (++rowCurrent >= MAX_CHARACTER_ROWS)
#if SCROLLMODE == 1 rowCurrent = 0;
// Finished if we've looped back to start }
if (rowNext == ROW_INITIAL) {
noMoreRowsToDisplay = true; uint8_t Display::countNonBlankRows() {
return false; uint8_t count = 0;
} for (uint8_t rowNumber=0; rowNumber<MAX_CHARACTER_ROWS; rowNumber++) {
#else if (rowBuffer[rowNumber][0] != '\0')
// Finished if we're back to the first one shown count++;
if (rowNext == rowFirst) {
noMoreRowsToDisplay = true;
return false;
}
#endif
if (rowBuffer[rowNext][0] != 0) {
// Found non-blank row
return true;
}
} }
return false; return count;
} }

View File

@@ -40,7 +40,6 @@ public:
static const int MAX_CHARACTER_ROWS = 8; static const int MAX_CHARACTER_ROWS = 8;
static const int MAX_CHARACTER_COLS = MAX_MSG_SIZE; static const int MAX_CHARACTER_COLS = MAX_MSG_SIZE;
static const long DISPLAY_SCROLL_TIME = 3000; // 3 seconds static const long DISPLAY_SCROLL_TIME = 3000; // 3 seconds
static const uint8_t ROW_INITIAL = 255;
private: private:
DisplayDevice *_deviceDriver; DisplayDevice *_deviceDriver;
@@ -48,16 +47,15 @@ private:
unsigned long lastScrollTime = 0; unsigned long lastScrollTime = 0;
uint8_t hotRow = 0; uint8_t hotRow = 0;
uint8_t hotCol = 0; uint8_t hotCol = 0;
uint8_t topRow = 0;
uint8_t slot = 0; uint8_t slot = 0;
uint8_t rowFirst = ROW_INITIAL; uint8_t rowFirst = 0;
uint8_t rowNext = ROW_INITIAL; uint8_t rowCurrent = 0;
uint8_t charIndex = 0; uint8_t charIndex = 0;
char buffer[MAX_CHARACTER_COLS + 1]; char buffer[MAX_CHARACTER_COLS + 1];
char* bufferPointer = 0; char* bufferPointer = 0;
bool noMoreRowsToDisplay = false; bool noMoreRowsToDisplay = false;
uint16_t numCharacterRows; uint16_t numScreenRows;
uint16_t numCharacterColumns = MAX_CHARACTER_COLS; uint16_t numScreenColumns = MAX_CHARACTER_COLS;
char rowBuffer[MAX_CHARACTER_ROWS][MAX_CHARACTER_COLS+1]; char rowBuffer[MAX_CHARACTER_ROWS][MAX_CHARACTER_COLS+1];
@@ -69,7 +67,10 @@ public:
void _refresh() override; void _refresh() override;
void _displayLoop() override; void _displayLoop() override;
Display *loop2(bool force); Display *loop2(bool force);
bool findNextNonBlankRow(); bool findNonBlankRow();
bool isCurrentRowBlank();
void moveToNextRow();
uint8_t countNonBlankRows();
}; };

View File

@@ -21,7 +21,7 @@
#include "DisplayInterface.h" #include "DisplayInterface.h"
// Start of chain of display handlers. // Install null display driver initially - will be replaced if required.
DisplayInterface *DisplayInterface::_displayHandler = NULL; DisplayInterface *DisplayInterface::_displayHandler = new DisplayInterface();
uint8_t DisplayInterface::_selectedDisplayNo = 255; uint8_t DisplayInterface::_selectedDisplayNo = 255;

View File

@@ -1,7 +1,7 @@
/* /*
* © 2021 Neil McKechnie * © 2021 Neil McKechnie
* © 2021-2023 Harald Barth * © 2021-2023 Harald Barth
* © 2020-2022 Chris Harlow * © 2020-2023 Chris Harlow
* All rights reserved. * All rights reserved.
* *
* This file is part of CommandStation-EX * This file is part of CommandStation-EX
@@ -24,8 +24,8 @@
F1. [DONE] DCC accessory packet opcodes (short and long form) F1. [DONE] DCC accessory packet opcodes (short and long form)
F2. [DONE] ONAccessory catchers F2. [DONE] ONAccessory catchers
F3. [DONE] Turnout descriptions for Withrottle F3. [DONE] Turnout descriptions for Withrottle
F4. Oled announcements (depends on HAL) F4. [DONE] Oled announcements (depends on HAL)
F5. Withrottle roster info F5. [DONE] Withrottle roster info
F6. Multi-occupancy semaphore F6. Multi-occupancy semaphore
F7. [DONE see AUTOSTART] Self starting sequences F7. [DONE see AUTOSTART] Self starting sequences
F8. Park/unpark F8. Park/unpark
@@ -105,12 +105,9 @@ uint16_t RMFT2::getOperand(byte n) {
// getOperand static version, must be provided prog counter from loop etc. // getOperand static version, must be provided prog counter from loop etc.
uint16_t RMFT2::getOperand(int progCounter,byte n) { uint16_t RMFT2::getOperand(int progCounter,byte n) {
int offset=progCounter+1+(n*3); int offset=progCounter+1+(n*3);
if (offset&1) { byte lsb=GETHIGHFLASH(RouteCode,offset);
byte lsb=GETHIGHFLASH(RouteCode,offset); byte msb=GETHIGHFLASH(RouteCode,offset+1);
byte msb=GETHIGHFLASH(RouteCode,offset+1); return msb<<8|lsb;
return msb<<8|lsb;
}
return GETHIGHFLASHW(RouteCode,offset);
} }
LookList::LookList(int16_t size) { LookList::LookList(int16_t size) {
@@ -201,7 +198,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
case OPCODE_IFNOT: { case OPCODE_IFNOT: {
int16_t pin = (int16_t)operand; int16_t pin = (int16_t)operand;
if (pin<0) pin = -pin; if (pin<0) pin = -pin;
DIAG(F("EXRAIL input vpin %d"),pin); DIAG(F("EXRAIL input VPIN %u"),pin);
IODevice::configureInput((VPIN)pin,true); IODevice::configureInput((VPIN)pin,true);
break; break;
} }
@@ -211,7 +208,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
case OPCODE_IFGTE: case OPCODE_IFGTE:
case OPCODE_IFLT: case OPCODE_IFLT:
case OPCODE_DRIVE: { case OPCODE_DRIVE: {
DIAG(F("EXRAIL analog input vpin %d"),(VPIN)operand); DIAG(F("EXRAIL analog input VPIN %u"),(VPIN)operand);
IODevice::configureAnalogIn((VPIN)operand); IODevice::configureAnalogIn((VPIN)operand);
break; break;
} }
@@ -243,8 +240,9 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
case OPCODE_AUTOSTART: case OPCODE_AUTOSTART:
// automatically create a task from here at startup. // automatically create a task from here at startup.
// but we will do one at 0 anyway by default. // Removed if (progCounter>0) check 4.2.31 because
if (progCounter>0) new RMFT2(progCounter); // default start it top of file is now removed. .
new RMFT2(progCounter);
break; break;
default: // Ignore default: // Ignore
@@ -255,7 +253,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
DIAG(F("EXRAIL %db, fl=%d"),progCounter,MAX_FLAGS); DIAG(F("EXRAIL %db, fl=%d"),progCounter,MAX_FLAGS);
new RMFT2(0); // add the startup route // Removed for 4.2.31 new RMFT2(0); // add the startup route
diag=saved_diag; diag=saved_diag;
} }

View File

@@ -136,7 +136,7 @@ bool EthernetInterface::checkLink() {
DIAG(F("Ethernet cable connected")); DIAG(F("Ethernet cable connected"));
connected=true; connected=true;
#ifdef IP_ADDRESS #ifdef IP_ADDRESS
setLocalIP(IP_ADDRESS); // for static IP, set it again Ethernet.setLocalIP(IP_ADDRESS); // for static IP, set it again
#endif #endif
IPAddress ip = Ethernet.localIP(); // look what IP was obtained (dynamic or static) IPAddress ip = Ethernet.localIP(); // look what IP was obtained (dynamic or static)
server = new EthernetServer(IP_PORT); // Ethernet Server listening on default port IP_PORT server = new EthernetServer(IP_PORT); // Ethernet Server listening on default port IP_PORT

View File

@@ -1 +1 @@
#define GITHUB_SHA "devel-202302121935Z" #define GITHUB_SHA "devel-202304071845Z"

View File

@@ -72,18 +72,23 @@ static const FSH * guessI2CDeviceType(uint8_t address) {
void I2CManagerClass::begin(void) { void I2CManagerClass::begin(void) {
if (!_beginCompleted) { if (!_beginCompleted) {
_beginCompleted = true; _beginCompleted = true;
// Check for short-circuit or floating lines (no pull-up) on I2C before enabling I2C
const FSH *message = F("WARNING: Check I2C %S line for short/pullup");
pinMode(SDA, INPUT);
if (!digitalRead(SDA))
DIAG(message, F("SDA"));
pinMode(SCL, INPUT);
if (!digitalRead(SCL))
DIAG(message, F("SCL"));
// Now initialise I2C
_initialise(); _initialise();
#if defined(I2C_USE_WIRE) #if defined(I2C_USE_WIRE)
DIAG(F("I2CManager: Using Wire library")); DIAG(F("I2CManager: Using Wire library"));
#endif #endif
// Check for short-circuits on I2C
if (!digitalRead(SDA))
DIAG(F("WARNING: Possible short-circuit on I2C SDA line"));
if (!digitalRead(SCL))
DIAG(F("WARNING: Possible short-circuit on I2C SCL line"));
// Probe and list devices. Use standard mode // Probe and list devices. Use standard mode
// (clock speed 100kHz) for best device compatibility. // (clock speed 100kHz) for best device compatibility.
_setClock(100000); _setClock(100000);

View File

@@ -84,8 +84,6 @@
*/ */
/* /*
* Future enhancement possibility:
*
* I2C Multiplexer (e.g. TCA9547, TCA9548) * I2C Multiplexer (e.g. TCA9547, TCA9548)
* *
* A multiplexer offers a way of extending the address range of I2C devices. For example, GPIO extenders use address range 0x20-0x27 * A multiplexer offers a way of extending the address range of I2C devices. For example, GPIO extenders use address range 0x20-0x27
@@ -98,11 +96,6 @@
* Thirdly, the multiplexer offers the ability to use mixed-speed devices more effectively, by allowing high-speed devices to be * Thirdly, the multiplexer offers the ability to use mixed-speed devices more effectively, by allowing high-speed devices to be
* put on a different bus to low-speed devices, enabling the software to switch the I2C speed on-the-fly between I2C transactions. * put on a different bus to low-speed devices, enabling the software to switch the I2C speed on-the-fly between I2C transactions.
* *
* Changes required: Increase the size of the I2CAddress field in the IODevice class from uint8_t to uint16_t.
* The most significant byte would contain a '1' bit flag, the multiplexer number (0-7) and bus number (0-7). Then, when performing
* an I2C operation, the I2CManager would check this byte and, if zero, do what it currently does. If the byte is non-zero, then
* that means the device is connected via a multiplexer so the I2C transaction should be preceded by a select command issued to the
* relevant multiplexer.
* *
* Non-interrupting I2C: * Non-interrupting I2C:
* *
@@ -138,13 +131,9 @@
// may be extended to include multiple buses, and other features. // may be extended to include multiple buses, and other features.
// Uncomment to enable extended address. // Uncomment to enable extended address.
// //
// WARNING: When I2CAddress is passed to formatting commands such as DIAG, LCD etc,
// it should be cast to (int) to ensure that the address value is passed rather than
// the struct.
//#define I2C_EXTENDED_ADDRESS //#define I2C_EXTENDED_ADDRESS
///////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////
// Extended I2C Address type to facilitate extended I2C addresses including // Extended I2C Address type to facilitate extended I2C addresses including
// I2C multiplexer support. // I2C multiplexer support.
@@ -184,7 +173,7 @@ enum I2CSubBus : uint8_t {
#endif #endif
SubBus_No, // Number of subbuses (highest + 1) SubBus_No, // Number of subbuses (highest + 1)
SubBus_None = 254, // Disable all sub-buses on selected mux SubBus_None = 254, // Disable all sub-buses on selected mux
SubBus_All = 255, // Enable all sub-buses SubBus_All = 255, // Enable all sub-buses (not supported by some multiplexers)
}; };
// Type to hold I2C address // Type to hold I2C address

View File

@@ -77,7 +77,15 @@ static uint8_t muxSelect(I2CAddress address) {
Wire.beginTransmission(I2C_MUX_BASE_ADDRESS+muxNo); Wire.beginTransmission(I2C_MUX_BASE_ADDRESS+muxNo);
uint8_t data = (subBus == SubBus_All) ? 0xff : uint8_t data = (subBus == SubBus_All) ? 0xff :
(subBus == SubBus_None) ? 0x00 : (subBus == SubBus_None) ? 0x00 :
(1 << subBus); #if defined(I2CMUX_PCA9547)
0x08 | subBus;
#elif defined(I2CMUX_PCA9542) || defined(I2CMUX_PCA9544)
0x04 | subBus; // NB Only 2 or 4 subbuses respectively
#else
// Default behaviour for most MUXs is to use a mask
// with a bit set for the subBus to be enabled
1 << subBus;
#endif
Wire.write(&data, 1); Wire.write(&data, 1);
return Wire.endTransmission(true); // have to release I2C bus for it to work return Wire.endTransmission(true); // have to release I2C bus for it to work
} }

View File

@@ -63,15 +63,31 @@ void IODevice::begin() {
if (exrailHalSetup) if (exrailHalSetup)
exrailHalSetup(); exrailHalSetup();
// Predefine two PCA9685 modules 0x40-0x41 // Predefine two PCA9685 modules 0x40-0x41 if no conflicts
// Allocates 32 pins 100-131 // Allocates 32 pins 100-131
PCA9685::create(100, 16, 0x40); if (checkNoOverlap(100, 16, 0x40)) {
PCA9685::create(116, 16, 0x41); PCA9685::create(100, 16, 0x40);
} else {
DIAG(F("Default PCA9685 at I2C 0x40 disabled due to configured user device"));
}
if (checkNoOverlap(116, 16, 0x41)) {
PCA9685::create(116, 16, 0x41);
} else {
DIAG(F("Default PCA9685 at I2C 0x41 disabled due to configured user device"));
}
// Predefine two MCP23017 module 0x20/0x21 // Predefine two MCP23017 module 0x20/0x21 if no conflicts
// Allocates 32 pins 164-195 // Allocates 32 pins 164-195
MCP23017::create(164, 16, 0x20); if (checkNoOverlap(164, 16, 0x20)) {
MCP23017::create(180, 16, 0x21); MCP23017::create(164, 16, 0x20);
} else {
DIAG(F("Default MCP23017 at I2C 0x20 disabled due to configured user device"));
}
if (checkNoOverlap(180, 16, 0x21)) {
MCP23017::create(180, 16, 0x21);
} else {
DIAG(F("Default MCP23017 at I2C 0x21 disabled due to configured user device"));
}
} }
// reset() function to reinitialise all devices // reset() function to reinitialise all devices
@@ -169,7 +185,7 @@ bool IODevice::hasCallback(VPIN vpin) {
// Display (to diagnostics) details of the device. // Display (to diagnostics) details of the device.
void IODevice::_display() { void IODevice::_display() {
DIAG(F("Unknown device Vpins:%d-%d %S"), DIAG(F("Unknown device Vpins:%u-%u %S"),
(int)_firstVpin, (int)_firstVpin+_nPins-1, _deviceState==DEVSTATE_FAILED ? F("OFFLINE") : F("")); (int)_firstVpin, (int)_firstVpin+_nPins-1, _deviceState==DEVSTATE_FAILED ? F("OFFLINE") : F(""));
} }
@@ -179,7 +195,7 @@ bool IODevice::configure(VPIN vpin, ConfigTypeEnum configType, int paramCount, i
IODevice *dev = findDevice(vpin); IODevice *dev = findDevice(vpin);
if (dev) return dev->_configure(vpin, configType, paramCount, params); if (dev) return dev->_configure(vpin, configType, paramCount, params);
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("IODevice::configure(): Vpin ID %d not found!"), (int)vpin); DIAG(F("IODevice::configure(): VPIN %u not found!"), (int)vpin);
#endif #endif
return false; return false;
} }
@@ -191,7 +207,7 @@ int IODevice::read(VPIN vpin) {
return dev->_read(vpin); return dev->_read(vpin);
} }
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("IODevice::read(): Vpin %d not found!"), (int)vpin); DIAG(F("IODevice::read(): VPIN %u not found!"), (int)vpin);
#endif #endif
return false; return false;
} }
@@ -203,7 +219,7 @@ int IODevice::readAnalogue(VPIN vpin) {
return dev->_readAnalogue(vpin); return dev->_readAnalogue(vpin);
} }
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("IODevice::readAnalogue(): Vpin %d not found!"), (int)vpin); DIAG(F("IODevice::readAnalogue(): VPIN %u not found!"), (int)vpin);
#endif #endif
return -1023; return -1023;
} }
@@ -213,7 +229,7 @@ int IODevice::configureAnalogIn(VPIN vpin) {
return dev->_configureAnalogIn(vpin); return dev->_configureAnalogIn(vpin);
} }
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("IODevice::configureAnalogIn(): Vpin %d not found!"), (int)vpin); DIAG(F("IODevice::configureAnalogIn(): VPIN %u not found!"), (int)vpin);
#endif #endif
return -1023; return -1023;
} }
@@ -227,7 +243,7 @@ void IODevice::write(VPIN vpin, int value) {
return; return;
} }
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("IODevice::write(): Vpin ID %d not found!"), (int)vpin); DIAG(F("IODevice::write(): VPIN %u not found!"), (int)vpin);
#endif #endif
} }
@@ -246,7 +262,7 @@ void IODevice::writeAnalogue(VPIN vpin, int value, uint8_t param1, uint16_t para
return; return;
} }
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("IODevice::writeAnalogue(): Vpin ID %d not found!"), (int)vpin); DIAG(F("IODevice::writeAnalogue(): VPIN %u not found!"), (int)vpin);
#endif #endif
} }
@@ -314,9 +330,11 @@ IODevice *IODevice::findDeviceFollowing(VPIN vpin) {
// Private helper function to check for vpin overlap. Run during setup only. // 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 DONT 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) { bool IODevice::checkNoOverlap(VPIN firstPin, uint8_t nPins, I2CAddress i2cAddress) {
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("Check no overlap %d %d %s"), firstPin,nPins,i2cAddress.toString()); DIAG(F("Check no overlap %u %u %s"), firstPin,nPins,i2cAddress.toString());
#endif #endif
VPIN lastPin=firstPin+nPins-1; VPIN lastPin=firstPin+nPins-1;
for (IODevice *dev = _firstDevice; dev != 0; dev = dev->_nextDevice) { for (IODevice *dev = _firstDevice; dev != 0; dev = dev->_nextDevice) {
@@ -327,7 +345,7 @@ bool IODevice::checkNoOverlap(VPIN firstPin, uint8_t nPins, I2CAddress i2cAddres
VPIN lastDevPin=firstDevPin+dev->_nPins-1; VPIN lastDevPin=firstDevPin+dev->_nPins-1;
bool noOverlap= firstPin>lastDevPin || lastPin<firstDevPin; bool noOverlap= firstPin>lastDevPin || lastPin<firstDevPin;
if (!noOverlap) { if (!noOverlap) {
DIAG(F("WARNING HAL Overlap definition of pins %d to %d ignored."), DIAG(F("WARNING HAL Overlap, redefinition of Vpins %u to %u ignored."),
firstPin, lastPin); firstPin, lastPin);
return false; return false;
} }
@@ -374,7 +392,7 @@ void IODevice::begin() { DIAG(F("NO HAL CONFIGURED!")); }
bool IODevice::configure(VPIN pin, ConfigTypeEnum configType, int nParams, int p[]) { bool IODevice::configure(VPIN pin, ConfigTypeEnum configType, int nParams, int p[]) {
if (configType!=CONFIGURE_INPUT || nParams!=1 || pin >= NUM_DIGITAL_PINS) return false; if (configType!=CONFIGURE_INPUT || nParams!=1 || pin >= NUM_DIGITAL_PINS) return false;
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("Arduino _configurePullup Pin:%d Val:%d"), pin, p[0]); DIAG(F("Arduino _configurePullup pin:%d Val:%d"), pin, p[0]);
#endif #endif
pinMode(pin, p[0] ? INPUT_PULLUP : INPUT); pinMode(pin, p[0] ? INPUT_PULLUP : INPUT);
return true; return true;
@@ -528,7 +546,7 @@ int ArduinoPins::_configureAnalogIn(VPIN vpin) {
} }
void ArduinoPins::_display() { void ArduinoPins::_display() {
DIAG(F("Arduino Vpins:%d-%d"), (int)_firstVpin, (int)_firstVpin+_nPins-1); DIAG(F("Arduino Vpins:%u-%u"), (int)_firstVpin, (int)_firstVpin+_nPins-1);
} }
///////////////////////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////////////////////

View File

@@ -467,6 +467,75 @@ protected:
} }
}; };
/////////////////////////////////////////////////////////////////////////////////////////////////////
//
// This HAL device driver is intended for communication in automation
// sequences. A VPIN can be SET or RESET within a sequence, and its
// current state checked elsewhere using IF, IFNOT, AT etc. or monitored
// from JMRI using a Sensor object (DCC-EX <S ...> command).
// Alternatively, the flag can be set from JMRI and other interfaces
// using the <Z ...> command, to enable or disable actions within a sequence.
//
// Example of configuration in halSetup.h:
//
// FLAGS::create(32000, 128);
//
// or in myAutomation.h:
//
// HAL(FLAGS, 32000, 128);
//
// Both create 128 flags numbered with VPINs 32000-32127.
//
//
class FLAGS : IODevice {
private:
uint8_t *_states = NULL;
public:
static void create(VPIN firstVpin, unsigned int nPins) {
if (checkNoOverlap(firstVpin, nPins))
new FLAGS(firstVpin, nPins);
}
protected:
// Constructor performs static initialisation of the device object
FLAGS (VPIN firstVpin, int nPins) {
_firstVpin = firstVpin;
_nPins = nPins;
_states = (uint8_t *)calloc(1, (_nPins+7)/8);
if (!_states) {
DIAG(F("FLAGS: ERROR Memory Allocation Failure"));
return;
}
addDevice(this);
}
int _read(VPIN vpin) override {
int pin = vpin - _firstVpin;
if (pin >= _nPins || pin < 0) return 0;
uint8_t mask = 1 << (pin & 7);
return (_states[pin>>3] & mask) ? 1 : 0;
}
void _write(VPIN vpin, int value) override {
int pin = vpin - _firstVpin;
if (pin >= _nPins || pin < 0) return;
uint8_t mask = 1 << (pin & 7);
if (value)
_states[pin>>3] |= mask;
else
_states[pin>>3] &= ~mask;
}
void _display() override {
DIAG(F("FLAGS configured on VPINs %u-%u"),
_firstVpin, _firstVpin+_nPins-1);
}
};
#include "IO_MCP23008.h" #include "IO_MCP23008.h"
#include "IO_MCP23017.h" #include "IO_MCP23017.h"
#include "IO_PCF8574.h" #include "IO_PCF8574.h"

View File

@@ -119,7 +119,7 @@ private:
case STATE_GETVALUE: case STATE_GETVALUE:
_value[_currentPin] = ((uint16_t)_inBuffer[0] << 8) + (uint16_t)_inBuffer[1]; _value[_currentPin] = ((uint16_t)_inBuffer[0] << 8) + (uint16_t)_inBuffer[1];
#ifdef IO_ANALOGUE_SLOW #ifdef IO_ANALOGUE_SLOW
DIAG(F("ADS111x pin:%d value:%d"), _currentPin, _value[_currentPin]); DIAG(F("ADS111x VPIN:%u value:%d"), _currentPin, _value[_currentPin]);
#endif #endif
// Move to next pin // Move to next pin
@@ -142,7 +142,7 @@ private:
} }
void _display() override { void _display() override {
DIAG(F("ADS111x I2C:%s Configured on Vpins:%d-%d %S"), _I2CAddress.toString(), _firstVpin, _firstVpin+_nPins-1, DIAG(F("ADS111x I2C:%s Configured on Vpins:%u-%u %S"), _I2CAddress.toString(), _firstVpin, _firstVpin+_nPins-1,
_deviceState == DEVSTATE_FAILED ? F("OFFLINE") : F("")); _deviceState == DEVSTATE_FAILED ? F("OFFLINE") : F(""));
} }

View File

@@ -62,7 +62,7 @@ void DCCAccessoryDecoder::_write(VPIN id, int state) {
void DCCAccessoryDecoder::_display() { void DCCAccessoryDecoder::_display() {
int endAddress = _packedAddress + _nPins - 1; int endAddress = _packedAddress + _nPins - 1;
DIAG(F("DCCAccessoryDecoder Configured on Vpins:%d-%d Addresses %d/%d-%d/%d)"), _firstVpin, _firstVpin+_nPins-1, DIAG(F("DCCAccessoryDecoder Configured on Vpins:%u-%u Addresses %d/%d-%d/%d)"), _firstVpin, _firstVpin+_nPins-1,
ADDRESS(_packedAddress), SUBADDRESS(_packedAddress), ADDRESS(endAddress), SUBADDRESS(endAddress)); ADDRESS(_packedAddress), SUBADDRESS(_packedAddress), ADDRESS(endAddress), SUBADDRESS(endAddress));
} }

View File

@@ -1,5 +1,5 @@
/* /*
* © 2022, Neil McKechnie. All rights reserved. * © 2023, Neil McKechnie. All rights reserved.
* *
* This file is part of DCC++EX API * This file is part of DCC++EX API
* *
@@ -33,10 +33,13 @@
* and Serialn is the name of the Serial port connected to the DFPlayer (e.g. Serial1). * and Serialn is the name of the Serial port connected to the DFPlayer (e.g. Serial1).
* *
* Example: * Example:
* In mySetup function within mySetup.cpp: * In halSetup function within myHal.cpp:
* DFPlayer::create(3500, 5, Serial1); * DFPlayer::create(3500, 5, Serial1);
* or in myAutomation.h:
* HAL(DFPlayer, 3500, 5, Serial1)
* *
* Writing an analogue value 1-2999 to the first pin (3500) will play the numbered file from the SD card; * Writing an analogue value 1-2999 to the first pin (3500) will play the numbered file from the
* SD card; e.g. a value of 1 will play the first file, 2 for the second file etc.
* Writing an analogue value 0 to the first pin (3500) will stop the file playing; * Writing an analogue value 0 to the first pin (3500) will stop the file playing;
* Writing an analogue value 0-30 to the second pin (3501) will set the volume; * Writing an analogue value 0-30 to the second pin (3501) will set the volume;
* Writing a digital value of 1 to a pin will play the file corresponding to that pin, e.g. * Writing a digital value of 1 to a pin will play the file corresponding to that pin, e.g.
@@ -61,6 +64,10 @@
* card (as listed by the DIR command in Windows). This may not match the order of the files * card (as listed by the DIR command in Windows). This may not match the order of the files
* as displayed by Windows File Manager, which sorts the file names. It is suggested that * as displayed by Windows File Manager, which sorts the file names. It is suggested that
* files be copied into an empty SDcard in the desired order, one at a time. * files be copied into an empty SDcard in the desired order, one at a time.
*
* The driver now polls the device for its current status every second. Should the device
* fail to respond it will be marked off-line and its busy indicator cleared, to avoid
* lock-ups in automation scripts that are executing for a WAITFOR().
*/ */
#ifndef IO_DFPlayer_h #ifndef IO_DFPlayer_h
@@ -74,21 +81,13 @@ private:
HardwareSerial *_serial; HardwareSerial *_serial;
bool _playing = false; bool _playing = false;
uint8_t _inputIndex = 0; uint8_t _inputIndex = 0;
unsigned long _commandSendTime; // Allows timeout processing unsigned long _commandSendTime; // Time (us) that last transmit took place.
uint8_t _lastVolumeLevel = MAXVOLUME; unsigned long _timeoutTime;
uint8_t _recvCMD; // Last received command code byte
// When two commands are sent in quick succession, the device sometimes bool _awaitingResponse = false;
// fails to execute one. A delay is required between successive commands. uint8_t _requestedVolumeLevel = MAXVOLUME;
// This could be implemented by buffering commands and outputting them uint8_t _currentVolume = MAXVOLUME;
// from the loop() function, but it would somewhat complicate the int _requestedSong = -1; // -1=none, 0=stop, >0=file number
// driver. A simpler solution is to output a number of NUL pad characters
// between successive command strings if there isn't sufficient elapsed time
// between them. At 9600 baud, each pad character takes approximately
// 1ms to complete. Experiments indicate that the minimum number of pads
// for reliable operation is 17. This gives 17.7ms between the end of one
// command and the beginning of the next, or 28ms between successive commands
// being completed. I've allowed 20 characters, which is almost 21ms.
const int numPadCharacters = 20; // Number of pad characters between commands
public: public:
@@ -113,66 +112,151 @@ protected:
// Send a query to the device to see if it responds // Send a query to the device to see if it responds
sendPacket(0x42); sendPacket(0x42);
_commandSendTime = micros(); _timeoutTime = micros() + 5000000UL; // 5 second timeout
_awaitingResponse = true;
} }
void _loop(unsigned long currentMicros) override { void _loop(unsigned long currentMicros) override {
// Check for incoming data on _serial, and update busy flag accordingly.
// Expected message is in the form "7E FF 06 3D xx xx xx xx xx EF" // Read responses from device
while (_serial->available()) { processIncoming();
int c = _serial->read();
if (c == 0x7E && _inputIndex == 0) // Check if a command sent to device has timed out. Allow 0.5 second for response
_inputIndex = 1; if (_awaitingResponse && (int32_t)(currentMicros - _timeoutTime) > 0) {
else if ((c==0xFF && _inputIndex==1)
|| (c==0x3D && _inputIndex==3)
|| (_inputIndex >=4 && _inputIndex <= 8))
_inputIndex++;
else if (c==0x06 && _inputIndex==2) {
// Valid message prefix, so consider the device online
if (_deviceState==DEVSTATE_INITIALISING) {
_deviceState = DEVSTATE_NORMAL;
#ifdef DIAG_IO
_display();
#endif
}
_inputIndex++;
} else if (c==0xEF && _inputIndex==9) {
// End of play
if (_playing) {
#ifdef DIAG_IO
DIAG(F("DFPlayer: Finished"));
#endif
_playing = false;
}
_inputIndex = 0;
} else
_inputIndex = 0; // Unrecognised character sequence, start again!
}
// Check if the initial prompt to device has timed out. Allow 5 seconds
if (_deviceState == DEVSTATE_INITIALISING && currentMicros - _commandSendTime > 5000000UL) {
DIAG(F("DFPlayer device not responding on serial port")); DIAG(F("DFPlayer device not responding on serial port"));
_deviceState = DEVSTATE_FAILED; _deviceState = DEVSTATE_FAILED;
_awaitingResponse = false;
_playing = false;
} }
// Send any commands that need to go.
processOutgoing(currentMicros);
delayUntil(currentMicros + 10000); // Only enter every 10ms delayUntil(currentMicros + 10000); // Only enter every 10ms
} }
// Check for incoming data on _serial, and update busy flag and other state accordingly
void processIncoming() {
// Expected message is in the form "7E FF 06 3D xx xx xx xx xx EF"
bool ok = false;
while (_serial->available()) {
int c = _serial->read();
switch (_inputIndex) {
case 0:
if (c == 0x7E) ok = true;
break;
case 1:
if (c == 0xFF) ok = true;
break;
case 2:
if (c== 0x06) ok = true;
break;
case 3:
_recvCMD = c; // CMD byte
ok = true;
break;
case 6:
switch (_recvCMD) {
case 0x42:
// Response to status query
_playing = (c != 0);
// Mark the device online and cancel timeout
if (_deviceState==DEVSTATE_INITIALISING) {
_deviceState = DEVSTATE_NORMAL;
#ifdef DIAG_IO
_display();
#endif
}
_awaitingResponse = false;
break;
case 0x3d:
// End of play
if (_playing) {
#ifdef DIAG_IO
DIAG(F("DFPlayer: Finished"));
#endif
_playing = false;
}
break;
case 0x40:
// Error code
DIAG(F("DFPlayer: Error %d returned from device"), c);
_playing = false;
break;
}
ok = true;
break;
case 4: case 5: case 7: case 8:
ok = true; // Skip over these bytes in message.
break;
case 9:
if (c==0xef) {
// Message finished
}
break;
default:
break;
}
if (ok)
_inputIndex++; // character as expected, so increment index
else
_inputIndex = 0; // otherwise reset.
}
}
// Send any commands that need to be sent
void processOutgoing(unsigned long currentMicros) {
// When two commands are sent in quick succession, the device will often fail to
// execute one. Testing has indicated that a delay of 100ms or more is required
// between successive commands to get reliable operation.
// If 100ms has elapsed since the last thing sent, then check if there's some output to do.
if (((int32_t)currentMicros - _commandSendTime) > 100000) {
if (_currentVolume > _requestedVolumeLevel) {
// Change volume before changing song if volume is reducing.
_currentVolume = _requestedVolumeLevel;
sendPacket(0x06, _currentVolume);
} else if (_requestedSong > 0) {
// Change song
sendPacket(0x03, _requestedSong);
_requestedSong = -1;
} else if (_requestedSong == 0) {
sendPacket(0x16); // Stop playing
_requestedSong = -1;
} else if (_currentVolume < _requestedVolumeLevel) {
// Change volume after changing song if volume is increasing.
_currentVolume = _requestedVolumeLevel;
sendPacket(0x06, _currentVolume);
} else if ((int32_t)currentMicros - _commandSendTime > 1000000) {
// Poll device every second that other commands aren't being sent,
// to check if it's still connected and responding.
sendPacket(0x42);
if (!_awaitingResponse) {
_timeoutTime = currentMicros + 5000000UL; // Timeout if no response within 5 seconds
_awaitingResponse = true;
}
}
}
}
// Write with value 1 starts playing a song. The relative pin number is the file number. // Write with value 1 starts playing a song. The relative pin number is the file number.
// Write with value 0 stops playing. // Write with value 0 stops playing.
void _write(VPIN vpin, int value) override { void _write(VPIN vpin, int value) override {
if (_deviceState == DEVSTATE_FAILED) return;
int pin = vpin - _firstVpin; int pin = vpin - _firstVpin;
if (value) { if (value) {
// Value 1, start playing // Value 1, start playing
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("DFPlayer: Play %d"), pin+1); DIAG(F("DFPlayer: Play %d"), pin+1);
#endif #endif
sendPacket(0x03, pin+1); _requestedSong = pin+1;
_playing = true; _playing = true;
} else { } else {
// Value 0, stop playing // Value 0, stop playing
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("DFPlayer: Stop")); DIAG(F("DFPlayer: Stop"));
#endif #endif
sendPacket(0x16); _requestedSong = 0; // No song
_playing = false; _playing = false;
} }
} }
@@ -181,16 +265,13 @@ protected:
// Volume may be specified as second parameter to writeAnalogue. // Volume may be specified as second parameter to writeAnalogue.
// If value is zero, the player stops playing. // If value is zero, the player stops playing.
// WriteAnalogue on second pin sets the output volume. // WriteAnalogue on second pin sets the output volume.
// If starting a new file and setting volume, then avoid a short burst of loud noise by
// the following strategy:
// - If the volume is increasing, start playing the song before setting the volume,
// - If the volume is decreasing, decrease it and then start playing.
// //
void _writeAnalogue(VPIN vpin, int value, uint8_t volume=0, uint16_t=0) override { void _writeAnalogue(VPIN vpin, int value, uint8_t volume=0, uint16_t=0) override {
if (_deviceState == DEVSTATE_FAILED) return;
uint8_t pin = vpin - _firstVpin; uint8_t pin = vpin - _firstVpin;
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("DFPlayer: VPIN:%d FileNo:%d Volume:%d"), vpin, value, volume); DIAG(F("DFPlayer: VPIN:%u FileNo:%d Volume:%d"), vpin, value, volume);
#endif #endif
// Validate parameter. // Validate parameter.
@@ -199,37 +280,28 @@ protected:
if (pin == 0) { if (pin == 0) {
// Play track // Play track
if (value > 0) { if (value > 0) {
if (volume != 0) { if (volume > 0)
if (volume <= _lastVolumeLevel) _requestedVolumeLevel = volume;
sendPacket(0x06, volume); // Set volume before starting _requestedSong = value;
sendPacket(0x03, value); // Play track _playing = true;
_playing = true;
if (volume > _lastVolumeLevel)
sendPacket(0x06, volume); // Set volume after starting
_lastVolumeLevel = volume;
} else {
// Volume not changed, just play
sendPacket(0x03, value);
_playing = true;
}
} else { } else {
sendPacket(0x16); // Stop play _requestedSong = 0; // stop playing
_playing = false; _playing = false;
} }
} else if (pin == 1) { } else if (pin == 1) {
// Set volume (0-30) // Set volume (0-30)
sendPacket(0x06, value); _requestedVolumeLevel = value;
_lastVolumeLevel = volume;
} }
} }
// A read on any pin indicates whether the player is still playing. // A read on any pin indicates whether the player is still playing.
int _read(VPIN) override { int _read(VPIN) override {
if (_deviceState == DEVSTATE_FAILED) return false;
return _playing; return _playing;
} }
void _display() override { void _display() override {
DIAG(F("DFPlayer Configured on Vpins:%d-%d %S"), _firstVpin, _firstVpin+_nPins-1, DIAG(F("DFPlayer Configured on Vpins:%u-%u %S"), _firstVpin, _firstVpin+_nPins-1,
(_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F("")); (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F(""));
} }
@@ -246,7 +318,6 @@ private:
void sendPacket(uint8_t command, uint16_t arg = 0) void sendPacket(uint8_t command, uint16_t arg = 0)
{ {
unsigned long currentMillis = millis();
uint8_t out[] = { 0x7E, uint8_t out[] = { 0x7E,
0xFF, 0xFF,
06, 06,
@@ -260,19 +331,10 @@ private:
setChecksum(out); setChecksum(out);
// Check how long since the last command was sent. // Output the command
// Each character takes approx 1ms at 9600 baud
unsigned long minimumGap = numPadCharacters + sizeof(out);
if (currentMillis - _commandSendTime < minimumGap) {
// Output some pad characters to add an
// artificial delay between commands
for (int i=0; i<numPadCharacters; i++)
_serial->write((uint8_t)0);
}
// Now output the command
_serial->write(out, sizeof(out)); _serial->write(out, sizeof(out));
_commandSendTime = currentMillis;
_commandSendTime = micros();
} }
uint16_t calcChecksum(uint8_t* packet) uint16_t calcChecksum(uint8_t* packet)

View File

@@ -34,11 +34,16 @@
* device in use. There is no way for the device driver to sanity check pins are used for the * device in use. There is no way for the device driver to sanity check pins are used for the
* correct purpose, however the EX-IOExpander device's pin map will prevent pins being used * correct purpose, however the EX-IOExpander device's pin map will prevent pins being used
* incorrectly (eg. A6/7 on Nano cannot be used for digital input/output). * incorrectly (eg. A6/7 on Nano cannot be used for digital input/output).
*
* The total number of pins cannot exceed 256 because of the communications packet format.
* The number of analogue inputs cannot exceed 16 because of a limit on the maximum
* I2C packet size of 32 bytes (in the Wire library).
*/ */
#ifndef IO_EX_IOEXPANDER_H #ifndef IO_EX_IOEXPANDER_H
#define IO_EX_IOEXPANDER_H #define IO_EX_IOEXPANDER_H
#include "IODevice.h"
#include "I2CManager.h" #include "I2CManager.h"
#include "DIAG.h" #include "DIAG.h"
#include "FSH.h" #include "FSH.h"
@@ -64,116 +69,209 @@ public:
if (checkNoOverlap(vpin, nPins, i2cAddress)) new EXIOExpander(vpin, nPins, i2cAddress); if (checkNoOverlap(vpin, nPins, i2cAddress)) new EXIOExpander(vpin, nPins, i2cAddress);
} }
private: private:
// Constructor // Constructor
EXIOExpander(VPIN firstVpin, int nPins, I2CAddress i2cAddress) { EXIOExpander(VPIN firstVpin, int nPins, I2CAddress i2cAddress) {
_firstVpin = firstVpin; _firstVpin = firstVpin;
// Number of pins cannot exceed 256 (1 byte) because of I2C message structure.
if (nPins > 256) nPins = 256;
_nPins = nPins; _nPins = nPins;
_i2cAddress = i2cAddress; _I2CAddress = i2cAddress;
addDevice(this); addDevice(this);
} }
void _begin() { void _begin() {
uint8_t status;
// Initialise EX-IOExander device // Initialise EX-IOExander device
I2CManager.begin(); I2CManager.begin();
if (I2CManager.exists(_i2cAddress)) { if (I2CManager.exists(_I2CAddress)) {
_command4Buffer[0] = EXIOINIT;
_command4Buffer[1] = _nPins;
_command4Buffer[2] = _firstVpin & 0xFF;
_command4Buffer[3] = _firstVpin >> 8;
// Send config, if EXIOPINS returned, we're good, setup pin buffers, otherwise go offline // Send config, if EXIOPINS returned, we're good, setup pin buffers, otherwise go offline
I2CManager.read(_i2cAddress, _receive3Buffer, 3, _command4Buffer, 4); // NB The I2C calls here are done as blocking calls, as they're not time-critical
if (_receive3Buffer[0] == EXIOPINS) { // during initialisation and the reads require waiting for a response anyway.
_numDigitalPins = _receive3Buffer[1]; // Hence we can allocate I/O buffers from the stack.
_numAnaloguePins = _receive3Buffer[2]; uint8_t receiveBuffer[3];
_digitalPinBytes = (_numDigitalPins + 7)/8; uint8_t commandBuffer[4] = {EXIOINIT, (uint8_t)_nPins, (uint8_t)(_firstVpin & 0xFF), (uint8_t)(_firstVpin >> 8)};
_digitalInputStates=(byte*) calloc(_digitalPinBytes,1); status = I2CManager.read(_I2CAddress, receiveBuffer, sizeof(receiveBuffer), commandBuffer, sizeof(commandBuffer));
_analoguePinBytes = _numAnaloguePins * 2; if (status == I2C_STATUS_OK) {
_analogueInputStates = (byte*) calloc(_analoguePinBytes, 1); if (receiveBuffer[0] == EXIOPINS) {
_analoguePinMap = (uint8_t*) calloc(_numAnaloguePins, 1); _numDigitalPins = receiveBuffer[1];
} else { _numAnaloguePins = receiveBuffer[2];
DIAG(F("ERROR configuring EX-IOExpander device, I2C:%s"), _i2cAddress.toString());
_deviceState = DEVSTATE_FAILED; // See if we already have suitable buffers assigned
return; size_t digitalBytesNeeded = (_numDigitalPins + 7) / 8;
} if (_digitalPinBytes < digitalBytesNeeded) {
// Not enough space, free any existing buffer and allocate a new one
if (_digitalPinBytes > 0) free(_digitalInputStates);
_digitalInputStates = (byte*) calloc(_digitalPinBytes, 1);
_digitalPinBytes = digitalBytesNeeded;
}
size_t analogueBytesNeeded = _numAnaloguePins * 2;
if (_analoguePinBytes < analogueBytesNeeded) {
// Free any existing buffers and allocate new ones.
if (_analoguePinBytes > 0) {
free(_analogueInputBuffer);
free(_analogueInputStates);
free(_analoguePinMap);
}
_analogueInputStates = (uint8_t*) calloc(analogueBytesNeeded, 1);
_analogueInputBuffer = (uint8_t*) calloc(analogueBytesNeeded, 1);
_analoguePinMap = (uint8_t*) calloc(_numAnaloguePins, 1);
_analoguePinBytes = analogueBytesNeeded;
}
} else {
DIAG(F("EX-IOExpander I2C:%s ERROR configuring device"), _I2CAddress.toString());
_deviceState = DEVSTATE_FAILED;
return;
}
}
// We now need to retrieve the analogue pin map // We now need to retrieve the analogue pin map
_command1Buffer[0] = EXIOINITA; if (status == I2C_STATUS_OK) {
I2CManager.read(_i2cAddress, _analoguePinMap, _numAnaloguePins, _command1Buffer, 1); commandBuffer[0] = EXIOINITA;
// Attempt to get version, if we don't get it, we don't care, don't go offline status = I2CManager.read(_I2CAddress, _analoguePinMap, _numAnaloguePins, commandBuffer, 1);
_command1Buffer[0] = EXIOVER; }
I2CManager.read(_i2cAddress, _versionBuffer, 3, _command1Buffer, 1); if (status == I2C_STATUS_OK) {
_majorVer = _versionBuffer[0]; // Attempt to get version, if we don't get it, we don't care, don't go offline
_minorVer = _versionBuffer[1]; uint8_t versionBuffer[3];
_patchVer = _versionBuffer[2]; commandBuffer[0] = EXIOVER;
DIAG(F("EX-IOExpander device found, I2C:%s, Version v%d.%d.%d"), if (I2CManager.read(_I2CAddress, versionBuffer, sizeof(versionBuffer), commandBuffer, 1) == I2C_STATUS_OK) {
_I2CAddress.toString(), _versionBuffer[0], _versionBuffer[1], _versionBuffer[2]); _majorVer = versionBuffer[0];
_minorVer = versionBuffer[1];
_patchVer = versionBuffer[2];
}
DIAG(F("EX-IOExpander device found, I2C:%s, Version v%d.%d.%d"),
_I2CAddress.toString(), _majorVer, _minorVer, _patchVer);
#ifdef DIAG_IO #ifdef DIAG_IO
_display(); _display();
#endif #endif
}
if (status != I2C_STATUS_OK)
reportError(status);
} else { } else {
DIAG(F("EX-IOExpander device not found, I2C:%s"), _I2CAddress.toString()); DIAG(F("EX-IOExpander I2C:%s device not found"), _I2CAddress.toString());
_deviceState = DEVSTATE_FAILED; _deviceState = DEVSTATE_FAILED;
} }
} }
// Digital input pin configuration, used to enable on EX-IOExpander device and set pullups if in use // Digital input pin configuration, used to enable on EX-IOExpander device and set pullups if requested.
// Configuration isn't done frequently so we can use blocking I2C calls here, and so buffers can
// be allocated from the stack to reduce RAM allocation.
bool _configure(VPIN vpin, ConfigTypeEnum configType, int paramCount, int params[]) override { bool _configure(VPIN vpin, ConfigTypeEnum configType, int paramCount, int params[]) override {
if (paramCount != 1) return false; if (paramCount != 1) return false;
int pin = vpin - _firstVpin; int pin = vpin - _firstVpin;
if (configType == CONFIGURE_INPUT) { if (configType == CONFIGURE_INPUT) {
bool pullup = params[0]; uint8_t pullup = params[0];
_digitalOutBuffer[0] = EXIODPUP; uint8_t outBuffer[] = {EXIODPUP, (uint8_t)pin, pullup};
_digitalOutBuffer[1] = pin; uint8_t responseBuffer[1];
_digitalOutBuffer[2] = pullup; uint8_t status = I2CManager.read(_I2CAddress, responseBuffer, sizeof(responseBuffer),
I2CManager.read(_i2cAddress, _command1Buffer, 1, _digitalOutBuffer, 3); outBuffer, sizeof(outBuffer));
if (_command1Buffer[0] == EXIORDY) { if (status == I2C_STATUS_OK) {
return true; if (responseBuffer[0] == EXIORDY) {
} else { return true;
DIAG(F("Vpin %d cannot be used as a digital input pin"), (int)vpin); } else {
return false; DIAG(F("EXIOVpin %u cannot be used as a digital input pin"), (int)vpin);
} }
} else { } else
reportError(status);
} else if (configType == CONFIGURE_ANALOGINPUT) {
// TODO: Consider moving code from _configureAnalogIn() to here and remove _configureAnalogIn
// from IODevice class definition. Not urgent, but each virtual function defined
// means increasing the RAM requirement of every HAL device driver, whether it's relevant
// to the driver or not.
return false; return false;
} }
return false;
} }
// Analogue input pin configuration, used to enable on EX-IOExpander device // Analogue input pin configuration, used to enable an EX-IOExpander device.
// Use I2C blocking calls and allocate buffers from stack to save RAM.
int _configureAnalogIn(VPIN vpin) override { int _configureAnalogIn(VPIN vpin) override {
int pin = vpin - _firstVpin; int pin = vpin - _firstVpin;
_command2Buffer[0] = EXIOENAN; uint8_t commandBuffer[] = {EXIOENAN, (uint8_t)pin};
_command2Buffer[1] = pin; uint8_t responseBuffer[1];
I2CManager.read(_i2cAddress, _command1Buffer, 1, _command2Buffer, 2); uint8_t status = I2CManager.read(_I2CAddress, responseBuffer, sizeof(responseBuffer),
if (_command1Buffer[0] == EXIORDY) { commandBuffer, sizeof(commandBuffer));
return true; if (status == I2C_STATUS_OK) {
} else { if (responseBuffer[0] == EXIORDY) {
DIAG(F("Vpin %d cannot be used as an analogue input pin"), (int)vpin); return true;
return false; } else {
} DIAG(F("EX-IOExpander: Vpin %u cannot be used as an analogue input pin"), (int)vpin);
return true; }
} else
reportError(status);
return false;
} }
// Main loop, collect both digital and analogue pin states continuously (faster sensor/input reads) // Main loop, collect both digital and analogue pin states continuously (faster sensor/input reads)
void _loop(unsigned long currentMicros) override { void _loop(unsigned long currentMicros) override {
(void)currentMicros; // remove warning if (_deviceState == DEVSTATE_FAILED) return; // If device failed, return
if (_deviceState == DEVSTATE_FAILED) return;
_command1Buffer[0] = EXIORDD; // Request block is used for analogue and digital reads from the IOExpander, which are performed
I2CManager.read(_i2cAddress, _digitalInputStates, _digitalPinBytes, _command1Buffer, 1); // on a cyclic basis. Writes are performed synchronously as and when requested.
_command1Buffer[0] = EXIORDAN;
I2CManager.read(_i2cAddress, _analogueInputStates, _analoguePinBytes, _command1Buffer, 1); if (_readState != RDS_IDLE) {
if (_i2crb.isBusy()) return; // If I2C operation still in progress, return
uint8_t status = _i2crb.status;
if (status == I2C_STATUS_OK) { // If device request ok, read input data
// First check if we need to process received data
if (_readState == RDS_ANALOGUE) {
// Read of analogue values was in progress, so process received values
// Here we need to copy the values from input buffer to the analogue value array. We need to
// do this to avoid tearing of the values (i.e. one byte of a two-byte value being changed
// while the value is being read).
memcpy(_analogueInputStates, _analogueInputBuffer, _analoguePinBytes); // Copy I2C input buffer to states
} else if (_readState == RDS_DIGITAL) {
// Read of digital states was in progress, so process received values
// The received digital states are placed directly into the digital buffer on receipt,
// so don't need any further processing at this point (unless we want to check for
// 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.
_readState = RDS_IDLE;
}
// If we're not doing anything now, check to see if a new input transfer is due.
if (_readState == RDS_IDLE) {
if (currentMicros - _lastDigitalRead > _digitalRefresh) { // Delay for digital read refresh
// Issue new read request for digital states. As the request is non-blocking, the buffer has to
// be allocated from heap (object state).
_readCommandBuffer[0] = EXIORDD;
I2CManager.read(_I2CAddress, _digitalInputStates, (_numDigitalPins+7)/8, _readCommandBuffer, 1, &_i2crb);
// non-blocking read
_lastDigitalRead = currentMicros;
_readState = RDS_DIGITAL;
} else if (currentMicros - _lastAnalogueRead > _analogueRefresh) { // Delay for analogue read refresh
// Issue new read for analogue input states
_readCommandBuffer[0] = EXIORDAN;
I2CManager.read(_I2CAddress, _analogueInputBuffer,
_numAnaloguePins * 2, _readCommandBuffer, 1, &_i2crb);
_lastAnalogueRead = currentMicros;
_readState = RDS_ANALOGUE;
}
}
} }
// Obtain the correct analogue input value, with reference to the analogue
// pin map.
// Obtain the correct analogue input value // Obtain the correct analogue input value
int _readAnalogue(VPIN vpin) override { int _readAnalogue(VPIN vpin) override {
if (_deviceState == DEVSTATE_FAILED) return 0; if (_deviceState == DEVSTATE_FAILED) return 0;
int pin = vpin - _firstVpin; int pin = vpin - _firstVpin;
uint8_t _pinLSBByte;
for (uint8_t aPin = 0; aPin < _numAnaloguePins; aPin++) { for (uint8_t aPin = 0; aPin < _numAnaloguePins; aPin++) {
if (_analoguePinMap[aPin] == pin) { if (_analoguePinMap[aPin] == pin) {
_pinLSBByte = aPin * 2; uint8_t _pinLSBByte = aPin * 2;
uint8_t _pinMSBByte = _pinLSBByte + 1;
return (_analogueInputStates[_pinMSBByte] << 8) + _analogueInputStates[_pinLSBByte];
} }
} }
uint8_t _pinMSBByte = _pinLSBByte + 1; return -1; // pin not found in table
return (_analogueInputStates[_pinMSBByte] << 8) + _analogueInputStates[_pinLSBByte];
} }
// Obtain the correct digital input value // Obtain the correct digital input value
@@ -185,63 +283,102 @@ private:
return value; return value;
} }
// Write digital value. We could have an output buffer of states, that is periodically
// written to the device if there are any changes; this would reduce the I2C overhead
// if lots of output requests are being made. We could also cache the last value
// sent so that we don't write the same value over and over to the output.
// However, for the time being, we just write the current value (blocking I2C) to the
// IOExpander node. As it is a blocking request, we can use buffers allocated from
// the stack to save RAM allocation.
void _write(VPIN vpin, int value) override { void _write(VPIN vpin, int value) override {
uint8_t digitalOutBuffer[3];
uint8_t responseBuffer[1];
if (_deviceState == DEVSTATE_FAILED) return; if (_deviceState == DEVSTATE_FAILED) return;
int pin = vpin - _firstVpin; int pin = vpin - _firstVpin;
_digitalOutBuffer[0] = EXIOWRD; digitalOutBuffer[0] = EXIOWRD;
_digitalOutBuffer[1] = pin; digitalOutBuffer[1] = pin;
_digitalOutBuffer[2] = value; digitalOutBuffer[2] = value;
I2CManager.read(_i2cAddress, _command1Buffer, 1, _digitalOutBuffer, 3); uint8_t status = I2CManager.read(_I2CAddress, responseBuffer, 1, digitalOutBuffer, 3);
if (_command1Buffer[0] != EXIORDY) { if (status != I2C_STATUS_OK) {
DIAG(F("Vpin %d cannot be used as a digital output pin"), (int)vpin); reportError(status);
} else {
if (responseBuffer[0] != EXIORDY) {
DIAG(F("Vpin %u cannot be used as a digital output pin"), (int)vpin);
}
} }
} }
// Write analogue (integer) value. Write the parameters (blocking I2C) to the
// IOExpander node. As it is a blocking request, we can use buffers allocated from
// the stack to reduce RAM allocation.
void _writeAnalogue(VPIN vpin, int value, uint8_t profile, uint16_t duration) override { void _writeAnalogue(VPIN vpin, int value, uint8_t profile, uint16_t duration) override {
uint8_t servoBuffer[7];
uint8_t responseBuffer[1];
if (_deviceState == DEVSTATE_FAILED) return; if (_deviceState == DEVSTATE_FAILED) return;
int pin = vpin - _firstVpin; int pin = vpin - _firstVpin;
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("Servo: WriteAnalogue Vpin:%d Value:%d Profile:%d Duration:%d %S"), DIAG(F("Servo: WriteAnalogue Vpin:%u Value:%d Profile:%d Duration:%d %S"),
vpin, value, profile, duration, _deviceState == DEVSTATE_FAILED?F("DEVSTATE_FAILED"):F("")); vpin, value, profile, duration, _deviceState == DEVSTATE_FAILED?F("DEVSTATE_FAILED"):F(""));
#endif #endif
_servoBuffer[0] = EXIOWRAN; servoBuffer[0] = EXIOWRAN;
_servoBuffer[1] = pin; servoBuffer[1] = pin;
_servoBuffer[2] = value & 0xFF; servoBuffer[2] = value & 0xFF;
_servoBuffer[3] = value >> 8; servoBuffer[3] = value >> 8;
_servoBuffer[4] = profile; servoBuffer[4] = profile;
_servoBuffer[5] = duration & 0xFF; servoBuffer[5] = duration & 0xFF;
_servoBuffer[6] = duration >> 8; servoBuffer[6] = duration >> 8;
I2CManager.read(_i2cAddress, _command1Buffer, 1, _servoBuffer, 7); uint8_t status = I2CManager.read(_I2CAddress, responseBuffer, 1, servoBuffer, 7);
if (_command1Buffer[0] != EXIORDY) { if (status != I2C_STATUS_OK) {
DIAG(F("Vpin %d cannot be used as a servo/PWM pin"), (int)vpin); DIAG(F("EX-IOExpander I2C:%s Error:%d %S"), _I2CAddress.toString(), status, I2CManager.getErrorMessage(status));
_deviceState = DEVSTATE_FAILED;
} else {
if (responseBuffer[0] != EXIORDY) {
DIAG(F("Vpin %u cannot be used as a servo/PWM pin"), (int)vpin);
}
} }
} }
// Display device information and status.
void _display() override { void _display() override {
DIAG(F("EX-IOExpander I2C:%s v%d.%d.%d Vpins %d-%d %S"), DIAG(F("EX-IOExpander I2C:%s v%d.%d.%d Vpins %u-%u %S"),
_i2cAddress.toString(), _majorVer, _minorVer, _patchVer, _I2CAddress.toString(), _majorVer, _minorVer, _patchVer,
(int)_firstVpin, (int)_firstVpin+_nPins-1, (int)_firstVpin, (int)_firstVpin+_nPins-1,
_deviceState == DEVSTATE_FAILED ? F("OFFLINE") : F("")); _deviceState == DEVSTATE_FAILED ? F("OFFLINE") : F(""));
} }
I2CAddress _i2cAddress; // Helper function for error handling
void reportError(uint8_t status, bool fail=true) {
DIAG(F("EX-IOExpander I2C:%s Error:%d (%S)"), _I2CAddress.toString(),
status, I2CManager.getErrorMessage(status));
if (fail)
_deviceState = DEVSTATE_FAILED;
}
uint8_t _numDigitalPins = 0; uint8_t _numDigitalPins = 0;
uint8_t _numAnaloguePins = 0; uint8_t _numAnaloguePins = 0;
byte _digitalOutBuffer[3];
uint8_t _versionBuffer[3];
uint8_t _majorVer = 0; uint8_t _majorVer = 0;
uint8_t _minorVer = 0; uint8_t _minorVer = 0;
uint8_t _patchVer = 0; uint8_t _patchVer = 0;
byte* _digitalInputStates;
byte* _analogueInputStates; uint8_t* _digitalInputStates;
uint8_t _digitalPinBytes = 0; uint8_t* _analogueInputStates;
uint8_t _analoguePinBytes = 0; uint8_t* _analogueInputBuffer; // buffer for I2C input transfers
byte _command1Buffer[1]; uint8_t _readCommandBuffer[1];
byte _command2Buffer[2];
byte _command4Buffer[4]; uint8_t _digitalPinBytes = 0; // Size of allocated memory buffer (may be longer than needed)
byte _receive3Buffer[3]; uint8_t _analoguePinBytes = 0; // Size of allocated memory buffers (may be longer than needed)
byte _servoBuffer[7];
uint8_t* _analoguePinMap; uint8_t* _analoguePinMap;
I2CRB _i2crb;
enum {RDS_IDLE, RDS_DIGITAL, RDS_ANALOGUE}; // Read operation states
uint8_t _readState = RDS_IDLE;
unsigned long _lastDigitalRead = 0;
unsigned long _lastAnalogueRead = 0;
const unsigned long _digitalRefresh = 10000UL; // Delay refreshing digital inputs for 10ms
const unsigned long _analogueRefresh = 50000UL; // Delay refreshing analogue inputs for 50ms
// EX-IOExpander protocol flags // EX-IOExpander protocol flags
enum { enum {

View File

@@ -103,7 +103,7 @@ void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_
uint8_t stepsMSB = value >> 8; uint8_t stepsMSB = value >> 8;
uint8_t stepsLSB = value & 0xFF; uint8_t stepsLSB = value & 0xFF;
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("EX-Turntable WriteAnalogue Vpin:%d Value:%d Activity:%d Duration:%d"), DIAG(F("EX-Turntable WriteAnalogue VPIN:%u Value:%d Activity:%d Duration:%d"),
vpin, value, activity, duration); vpin, value, activity, duration);
DIAG(F("I2CManager write I2C Address:%d stepsMSB:%d stepsLSB:%d activity:%d"), DIAG(F("I2CManager write I2C Address:%d stepsMSB:%d stepsLSB:%d activity:%d"),
_I2CAddress.toString(), stepsMSB, stepsLSB, activity); _I2CAddress.toString(), stepsMSB, stepsLSB, activity);
@@ -114,7 +114,7 @@ void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_
// Display Turnetable-EX device driver info. // Display Turnetable-EX device driver info.
void EXTurntable::_display() { void EXTurntable::_display() {
DIAG(F("EX-Turntable I2C:%s Configured on Vpins:%d-%d %S"), _I2CAddress.toString(), (int)_firstVpin, 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("")); (int)_firstVpin+_nPins-1, (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F(""));
} }

View File

@@ -84,7 +84,7 @@ protected:
void _write(VPIN vpin, int value) { void _write(VPIN vpin, int value) {
int pin = vpin -_firstVpin; int pin = vpin -_firstVpin;
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("IO_ExampleSerial::_write Pin:%d Value:%d"), (int)vpin, value); DIAG(F("IO_ExampleSerial::_write VPIN:%u Value:%d"), (int)vpin, value);
#endif #endif
// Send a command string over the serial line // Send a command string over the serial line
_serial->print('#'); _serial->print('#');
@@ -153,10 +153,10 @@ protected:
// Display information about the device, and perhaps its current condition (e.g. active, disabled etc). // Display information about the device, and perhaps its current condition (e.g. active, disabled etc).
// Here we display the current values held for the pins. // Here we display the current values held for the pins.
void _display() { void _display() {
DIAG(F("IO_ExampleSerial Configured on VPins:%d-%d"), (int)_firstVpin, DIAG(F("IO_ExampleSerial Configured on Vpins:%u-%u"), (int)_firstVpin,
(int)_firstVpin+_nPins-1); (int)_firstVpin+_nPins-1);
for (int i=0; i<_nPins; i++) for (int i=0; i<_nPins; i++)
DIAG(F(" VPin %2d: %d"), _firstVpin+i, _pinValues[i]); DIAG(F(" VPin %2u: %d"), _firstVpin+i, _pinValues[i]);
} }

View File

@@ -1,141 +0,0 @@
/*
* © 2023, Neil McKechnie. All rights reserved.
*
* This file is part of DCC++EX API
*
* 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/>.
*/
/*
* This device driver monitors the state of turnout objects and writes updates,
* on change of state, to an external 24C128 (16kByte) or 24C256 (32kByte)
* EEPROM device connected via I2C.
*
* When the device is restarted, it repositions the turnouts in accordance
* with the last saved position.
*
* To create a device instance,
* IO_ExternalEEPROM::create(0, 0, i2cAddress);
*
*
*/
#ifndef IO_EXTERNALEEPROM_H
#define IO_EXTERNALEEPROM_H
#include "IODevice.h"
#include "I2CManager.h"
#include "Turnouts.h"
class ExternalEEPROM : public IODevice {
private:
// Here we define the device-specific variables.
int _sizeInKBytes = 128;
Turnout *_turnout = 0;
int _lastTurnoutHash = 0;
I2CRB _rb;
uint8_t _buffer[32]; // 32 is max for Wire write
public:
// Static function to handle "IO_ExampleSerial::create(...)" calls.
static void create(I2CAddress i2cAddress, int sizeInKBytes) {
if (checkNoOverlap(0, 0, i2cAddress)) new ExternalEEPROM(i2cAddress, sizeInKBytes);
}
protected:
// Constructor.
ExternalEEPROM(I2CAddress i2cAddress, int sizeInKBytes) {
_I2CAddress = i2cAddress;
_sizeInKBytes = sizeInKBytes;
// Set up I2C structures.
_rb.setWriteParams(_I2CAddress, _buffer, 32);
addDevice(this);
}
// Device-specific initialisation
void _begin() override {
I2CManager.begin();
I2CManager.setClock(1000000); // Max supported speed
if (I2CManager.exists(_I2CAddress)) {
// Initialise or read contents of EEPROM
// and set turnout states accordingly.
// Read 32 bytes from address 0x0000.
I2CManager.read(_I2CAddress, _buffer, 32, 2, 0, 0);
// Dump data
DIAG(F("EEPROM First 32 bytes:"));
for (int i=0; i<32; i+=8)
DIAG(F("%d: %x %x %x %x %x %x %x %x"),
i, _buffer[i], _buffer[i+1], _buffer[i+2], _buffer[i+3],
_buffer[i+4], _buffer[i+5], _buffer[i+6], _buffer[i+7]);
#if defined(DIAG_IO)
_display();
#endif
} else {
DIAG(F("ExternalEEPROM not found, I2C:%s"), _I2CAddress.toString());
_deviceState = DEVSTATE_FAILED;
}
}
// Loop function to do background scanning of the turnouts
void _loop(unsigned long currentMicros) {
(void)currentMicros; // Suppress compiler warnings
if (_rb.isBusy()) return; // Can't do anything until previous request has completed.
if (_rb.status == I2C_STATUS_NEGATIVE_ACKNOWLEDGE) {
// Device not responding, probably still writing data, so requeue request
I2CManager.queueRequest(&_rb);
return;
}
if (_lastTurnoutHash != Turnout::turnoutlistHash) {
_lastTurnoutHash = Turnout::turnoutlistHash;
// Turnout list has changed, so pointer held from last run may be invalid
_turnout = 0; // Start at the beginning of the list again.
//#if defined(DIAG_IO)
DIAG(F("Turnout Hash Changed!"));
//#endif
}
// Locate next turnout, or first one if there is no current one.
if (_turnout)
_turnout = _turnout->next();
else
_turnout = Turnout::first();
// Retrieve turnout state
int turnoutID = _turnout->getId();
int turnoutState = _turnout->isThrown();
(void)turnoutID; // Suppress compiler warning
(void)turnoutState; // Suppress compiler warning
// TODO: Locate turnoutID in EEPROM (or EEPROM copy) and check if state has changed.
// TODO: If it has, then initiate a write of the updated state to EEPROM
delayUntil(currentMicros+5000); // Write cycle time is 5ms max for FT24C256
}
// Display information about the device.
void _display() {
DIAG(F("ExternalEEPROM %dkBytes I2C:%s %S"), _sizeInKBytes, _I2CAddress.toString(),
_deviceState== DEVSTATE_FAILED ? F("OFFLINE") : F(""));
}
};
#endif // IO_EXTERNALEEPROM_H

View File

@@ -196,7 +196,7 @@ void GPIOBase<T>::_loop(unsigned long currentMicros) {
template <class T> template <class T>
void GPIOBase<T>::_display() { void GPIOBase<T>::_display() {
DIAG(F("%S I2C:%s Configured on Vpins:%d-%d %S"), _deviceName, _I2CAddress.toString(), DIAG(F("%S I2C:%s Configured on Vpins:%u-%u %S"), _deviceName, _I2CAddress.toString(),
_firstVpin, _firstVpin+_nPins-1, (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F("")); _firstVpin, _firstVpin+_nPins-1, (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F(""));
} }

View File

@@ -76,21 +76,23 @@ private:
uint8_t *_lastRowGeneration = NULL; uint8_t *_lastRowGeneration = NULL;
uint8_t _rowNoToScreen = 0; uint8_t _rowNoToScreen = 0;
uint8_t _charPosToScreen = 0; uint8_t _charPosToScreen = 0;
bool _startAgain = false;
DisplayInterface *_nextDisplay = NULL; DisplayInterface *_nextDisplay = NULL;
public: public:
// Static function to handle "HALDisplay::create(...)" calls. // Static function to handle "HALDisplay::create(...)" calls.
static void create(I2CAddress i2cAddress, int width, int height) { static void create(I2CAddress i2cAddress, int width, int height) {
/* if (checkNoOverlap(i2cAddress)) */ new HALDisplay(0, i2cAddress, width, height); if (checkNoOverlap(0, 0, i2cAddress)) new HALDisplay(0, i2cAddress, width, height);
} }
static void create(uint8_t displayNo, I2CAddress i2cAddress, int width, int height) { static void create(uint8_t displayNo, I2CAddress i2cAddress, int width, int height) {
/* if (checkNoOverlap(i2cAddress)) */ new HALDisplay(displayNo, i2cAddress, width, height); if (checkNoOverlap(0, 0, i2cAddress)) new HALDisplay(displayNo, i2cAddress, width, height);
} }
protected: protected:
// Constructor // Constructor
HALDisplay(uint8_t displayNo, I2CAddress i2cAddress, int width, int height) { HALDisplay(uint8_t displayNo, I2CAddress i2cAddress, int width, int height) {
_displayDriver = new T(i2cAddress, width, height); _displayDriver = new T(i2cAddress, width, height);
if (!_displayDriver) return; // Check for memory allocation failure
_I2CAddress = i2cAddress; _I2CAddress = i2cAddress;
_width = width; _width = width;
_height = height; _height = height;
@@ -101,8 +103,12 @@ protected:
// Allocate arrays // Allocate arrays
_buffer = (char *)calloc(_numRows*_numCols, sizeof(char)); _buffer = (char *)calloc(_numRows*_numCols, sizeof(char));
if (!_buffer) return; // Check for memory allocation failure
_rowGeneration = (uint8_t *)calloc(_numRows, sizeof(uint8_t)); _rowGeneration = (uint8_t *)calloc(_numRows, sizeof(uint8_t));
if (!_rowGeneration) return; // Check for memory allocation failure
_lastRowGeneration = (uint8_t *)calloc(_numRows, sizeof(uint8_t)); _lastRowGeneration = (uint8_t *)calloc(_numRows, sizeof(uint8_t));
if (!_lastRowGeneration) return; // Check for memory allocation failure
// Fill buffer with spaces // Fill buffer with spaces
memset(_buffer, ' ', _numCols*_numRows); memset(_buffer, ' ', _numCols*_numRows);
@@ -116,7 +122,7 @@ protected:
// Also add this display to list of display handlers // Also add this display to list of display handlers
DisplayInterface::addDisplay(displayNo); DisplayInterface::addDisplay(displayNo);
// Is this the main display? // Is this the system display (0)?
if (displayNo == 0) { if (displayNo == 0) {
// Set first two lines on screen // Set first two lines on screen
this->setRow(displayNo, 0); this->setRow(displayNo, 0);
@@ -135,13 +141,15 @@ protected:
// to the screen until that row has been refreshed. // to the screen until that row has been refreshed.
// First check if the OLED driver is still busy from a previous // First check if the OLED driver is still busy from a previous
// call. If so, don't to anything until the next entry. // call. If so, don't do anything until the next entry.
if (!_displayDriver->isBusy()) { if (!_displayDriver->isBusy()) {
// Check if we've just done the end of a row // Check if we've just done the end of a row
if (_charPosToScreen >= _numCols) { if (_charPosToScreen >= _numCols) {
// Move to next line // Move to next line
if (++_rowNoToScreen >= _numRows) if (++_rowNoToScreen >= _numRows || _startAgain) {
_rowNoToScreen = 0; // Wrap to first row _rowNoToScreen = 0; // Wrap to first row
_startAgain = false;
}
if (_rowGeneration[_rowNoToScreen] != _lastRowGeneration[_rowNoToScreen]) { if (_rowGeneration[_rowNoToScreen] != _lastRowGeneration[_rowNoToScreen]) {
// Row content has changed, so start outputting it // Row content has changed, so start outputting it
@@ -222,10 +230,14 @@ public:
for (_colNo = 0; _colNo < _numCols; _colNo++) for (_colNo = 0; _colNo < _numCols; _colNo++)
_buffer[_rowNo*_numCols+_colNo] = ' '; _buffer[_rowNo*_numCols+_colNo] = ' ';
_colNo = 0; _colNo = 0;
// Mark that the buffer has been touched. It will be // Mark that the buffer has been touched. It will start being
// sent to the screen on the next loop entry, by which time // sent to the screen on the next loop entry, by which time
// the line should have been written to the buffer. // the line should have been written to the buffer.
_rowGeneration[_rowNo]++; _rowGeneration[_rowNo]++;
// Indicate that the output loop is to start updating the screen again from
// row 0. Otherwise, on a full screen rewrite the bottom part may be drawn
// before the top part!
_startAgain = true;
} }
// Write one character to the screen referenced in the last setRow() call. // Write one character to the screen referenced in the last setRow() call.

View File

@@ -30,7 +30,7 @@
* *
* This driver polls the HC-SR04 by sending the trigger pulse and then measuring * This driver polls the HC-SR04 by sending the trigger pulse and then measuring
* the length of the received pulse. If the calculated distance is less than * the length of the received pulse. If the calculated distance is less than
* the threshold, the output state returned by a read() call changes to 1. If * the threshold, the output _state returned by a read() call changes to 1. If
* the distance is greater than the threshold plus a hysteresis margin, the * the distance is greater than the threshold plus a hysteresis margin, the
* output changes to 0. The device also supports readAnalogue(), which returns * output changes to 0. The device also supports readAnalogue(), which returns
* the measured distance in cm, or 32767 if the distance exceeds the * the measured distance in cm, or 32767 if the distance exceeds the
@@ -48,6 +48,20 @@
* Note: The timing accuracy required for measuring the pulse length means that * Note: The timing accuracy required for measuring the pulse length means that
* the pins have to be direct Arduino pins; GPIO pins on an IO Extender cannot * the pins have to be direct Arduino pins; GPIO pins on an IO Extender cannot
* provide the required accuracy. * provide the required accuracy.
*
* Example configuration:
* HCSR04::create(23000, 32, 33, 80, 85);
*
* Where 23000 is the VPIN allocated,
* 32 is the pin connected to the HCSR04 trigger terminal,
* 33 is the pin connected to the HCSR04 echo terminal,
* 80 is the distance in cm below which pin 23000 will be active,
* and 85 is the distance in cm above which pin 23000 will be inactive.
*
* Alternative configuration, which hogs the processor until the measurement is complete
* (old behaviour, more accurate but higher impact on other CS tasks):
* HCSR04::create(23000, 32, 33, 80, 85, HCSR04::LOOP);
*
*/ */
#ifndef IO_HCSR04_H #ifndef IO_HCSR04_H
@@ -61,38 +75,52 @@ private:
// pins must be arduino GPIO pins, not extender pins or HAL pins. // pins must be arduino GPIO pins, not extender pins or HAL pins.
int _trigPin = -1; int _trigPin = -1;
int _echoPin = -1; int _echoPin = -1;
// Thresholds for setting active state in cm. // Thresholds for setting active _state in cm.
uint8_t _onThreshold; // cm uint8_t _onThreshold; // cm
uint8_t _offThreshold; // cm uint8_t _offThreshold; // cm
// Last measured distance in cm. // Last measured distance in cm.
uint16_t _distance; uint16_t _distance;
// Active=1/inactive=0 state // Active=1/inactive=0 _state
uint8_t _value = 0; uint8_t _value = 0;
// Factor for calculating the distance (cm) from echo time (ms). // Factor for calculating the distance (cm) from echo time (us).
// Based on a speed of sound of 345 metres/second. // Based on a speed of sound of 345 metres/second.
const uint16_t factor = 58; // ms/cm const uint16_t factor = 58; // us/cm
// Limit the time spent looping by dropping out when the expected
// worst case threshold value is greater than an arbitrary value.
const uint16_t maxPermittedLoopTime = 10 * factor; // max in us
unsigned long _startTime = 0;
unsigned long _maxTime = 0;
enum {DORMANT, MEASURING}; // _state values
uint8_t _state = DORMANT;
uint8_t _counter = 0;
uint16_t _options = 0;
public: public:
enum Options {
LOOP = 1, // Option HCSR04::LOOP reinstates old behaviour, i.e. complete measurement in one loop entry.
};
// Static create function provides alternative way to create object // Static create function provides alternative way to create object
static void create(VPIN vpin, int trigPin, int echoPin, uint16_t onThreshold, uint16_t offThreshold) { static void create(VPIN vpin, int trigPin, int echoPin, uint16_t onThreshold, uint16_t offThreshold, uint16_t options = 0) {
if (checkNoOverlap(vpin)) if (checkNoOverlap(vpin))
new HCSR04(vpin, trigPin, echoPin, onThreshold, offThreshold); new HCSR04(vpin, trigPin, echoPin, onThreshold, offThreshold, options);
} }
protected: protected:
// Constructor perfroms static initialisation of the device object // Constructor performs static initialisation of the device object
HCSR04 (VPIN vpin, int trigPin, int echoPin, uint16_t onThreshold, uint16_t offThreshold) { HCSR04 (VPIN vpin, int trigPin, int echoPin, uint16_t onThreshold, uint16_t offThreshold, uint16_t options) {
_firstVpin = vpin; _firstVpin = vpin;
_nPins = 1; _nPins = 1;
_trigPin = trigPin; _trigPin = trigPin;
_echoPin = echoPin; _echoPin = echoPin;
_onThreshold = onThreshold; _onThreshold = onThreshold;
_offThreshold = offThreshold; _offThreshold = offThreshold;
_options = options;
addDevice(this); addDevice(this);
} }
// _begin function called to perform dynamic initialisation of the device // _begin function called to perform dynamic initialisation of the device
void _begin() override { void _begin() override {
_state = 0;
pinMode(_trigPin, OUTPUT); pinMode(_trigPin, OUTPUT);
pinMode(_echoPin, INPUT); pinMode(_echoPin, INPUT);
ArduinoPins::fastWriteDigital(_trigPin, 0); ArduinoPins::fastWriteDigital(_trigPin, 0);
@@ -112,78 +140,104 @@ protected:
return _distance; return _distance;
} }
// _loop function - read HC-SR04 once every 50 milliseconds. // _loop function - read HC-SR04 once every 100 milliseconds.
void _loop(unsigned long currentMicros) override { void _loop(unsigned long currentMicros) override {
read_HCSR04device(); unsigned long waitTime;
// Delay next loop entry until 50ms have elapsed. switch(_state) {
delayUntil(currentMicros + 50000UL); case DORMANT: // Issue pulse
// If receive pin is still set on from previous call, do nothing till next entry.
if (ArduinoPins::fastReadDigital(_echoPin)) return;
// Send 10us pulse to trigger transmitter
ArduinoPins::fastWriteDigital(_trigPin, 1);
delayMicroseconds(10);
ArduinoPins::fastWriteDigital(_trigPin, 0);
// Wait, with timeout, for echo pin to become set.
// Measured time delay is just under 500us, so
// wait for max of 1000us.
_startTime = micros();
_maxTime = 1000;
while (!ArduinoPins::fastReadDigital(_echoPin)) {
// Not set yet, see if we've timed out.
waitTime = micros() - _startTime;
if (waitTime > _maxTime) {
// Timeout waiting for pulse start, abort the read and start again
_state = DORMANT;
return;
}
}
// Echo pulse started, so wait for echo pin to reset, and measure length of pulse
_startTime = micros();
_maxTime = factor * _offThreshold;
_state = MEASURING;
// If maximum measurement time is high, then skip until next loop entry before
// starting to look for pulse end.
// This gives better accuracy at shorter distance thresholds but without extending
// loop execution time for longer thresholds. If LOOP option is set on, then
// the entire measurement will be done in one loop entry, i.e. the code will fall
// through into the measuring phase.
if (!(_options & LOOP) && _maxTime > maxPermittedLoopTime) break;
/* fallthrough */
case MEASURING: // Check if echo pulse has finished
do {
waitTime = micros() - _startTime;
if (!ArduinoPins::fastReadDigital(_echoPin)) {
// Echo pulse completed; check if pulse length is below threshold and if so set value.
if (waitTime <= factor * _onThreshold) {
// Measured time is within the onThreshold, so value is one.
_value = 1;
// If the new distance value is less than the current, use it immediately.
// But if the new distance value is longer, then it may be erroneously long
// (because of extended loop times delays), so apply a delay to distance increases.
uint16_t estimatedDistance = waitTime / factor;
if (estimatedDistance < _distance)
_distance = estimatedDistance;
else
_distance += 1; // Just increase distance slowly.
_counter = 0;
//DIAG(F("HCSR04: Pulse Len=%l Distance=%d"), waitTime, _distance);
}
_state = DORMANT;
} else {
// Echo pulse hasn't finished, so check if maximum time has elapsed
// If pulse is too long then set return value to zero,
// and finish without waiting for end of pulse.
if (waitTime > _maxTime) {
// Pulse length longer than maxTime, value is provisionally zero.
// But don't change _value unless provisional value is zero for 10 consecutive measurements
if (_value == 1) {
if (++_counter >= 10) {
_value = 0;
_distance = 32767;
_counter = 0;
}
}
_state = DORMANT; // start again
}
}
// If there's lots of time remaining before the expected completion time,
// then exit and wait for next loop entry. Otherwise, loop until we finish.
// If option LOOP is set, then we loop until finished anyway.
uint32_t remainingTime = _maxTime - waitTime;
if (!(_options & LOOP) && remainingTime < maxPermittedLoopTime) return;
} while (_state == MEASURING) ;
break;
}
// Datasheet recommends a wait of at least 60ms between measurement cycles
if (_state == DORMANT)
delayUntil(currentMicros+60000UL); // wait 60ms till next measurement
} }
void _display() override { void _display() override {
DIAG(F("HCSR04 Configured on Vpin:%d TrigPin:%d EchoPin:%d On:%dcm Off:%dcm"), DIAG(F("HCSR04 Configured on VPIN:%u TrigPin:%d EchoPin:%d On:%dcm Off:%dcm"),
_firstVpin, _trigPin, _echoPin, _onThreshold, _offThreshold); _firstVpin, _trigPin, _echoPin, _onThreshold, _offThreshold);
} }
private:
// This polls the HC-SR04 device by sending a pulse and measuring the duration of
// the pulse observed on the receive pin. In order to be kind to the rest of the CS
// software, no interrupts are used and interrupts are not disabled. The pulse duration
// is measured in a loop, using the micros() function. Therefore, interrupts from other
// sources may affect the result. However, interrupts response code in CS typically takes
// much less than the 58us frequency for the DCC interrupt, and 58us corresponds to only 1cm
// in the HC-SR04.
// To reduce chatter on the output, hysteresis is applied on reset: the output is set to 1 when the
// measured distance is less than the onThreshold, and is set to 0 if the measured distance is
// greater than the offThreshold.
//
void read_HCSR04device() {
// uint16 enough to time up to 65ms
uint16_t startTime, waitTime = 0, currentTime, maxTime;
// If receive pin is still set on from previous call, abort the read.
if (ArduinoPins::fastReadDigital(_echoPin))
return;
// Send 10us pulse to trigger transmitter
ArduinoPins::fastWriteDigital(_trigPin, 1);
delayMicroseconds(10);
ArduinoPins::fastWriteDigital(_trigPin, 0);
// Wait for receive pin to be set
startTime = currentTime = micros();
maxTime = factor * _offThreshold * 2;
while (!ArduinoPins::fastReadDigital(_echoPin)) {
// lastTime = currentTime;
currentTime = micros();
waitTime = currentTime - startTime;
if (waitTime > maxTime) {
// Timeout waiting for pulse start, abort the read
return;
}
}
// Wait for receive pin to reset, and measure length of pulse
startTime = currentTime = micros();
maxTime = factor * _offThreshold;
while (ArduinoPins::fastReadDigital(_echoPin)) {
currentTime = micros();
waitTime = currentTime - startTime;
// If pulse is too long then set return value to zero,
// and finish without waiting for end of pulse.
if (waitTime > maxTime) {
// Pulse length longer than maxTime, reset value.
_value = 0;
_distance = 32767;
return;
}
}
// Check if pulse length is below threshold, if so set value.
//DIAG(F("HCSR04: Pulse Len=%l Distance=%d"), waitTime, distance);
_distance = waitTime / factor; // in centimetres
if (_distance < _onThreshold)
_value = 1;
}
}; };
#endif //IO_HCSR04_H #endif //IO_HCSR04_H

View File

@@ -45,8 +45,8 @@ void PCA9685::create(VPIN firstVpin, int nPins, I2CAddress i2cAddress, uint16_t
bool PCA9685::_configure(VPIN vpin, ConfigTypeEnum configType, int paramCount, int params[]) { bool PCA9685::_configure(VPIN vpin, ConfigTypeEnum configType, int paramCount, int params[]) {
if (configType != CONFIGURE_SERVO) return false; if (configType != CONFIGURE_SERVO) return false;
if (paramCount != 5) return false; if (paramCount != 5) return false;
#if DIAG_IO >= 3 #ifdef DIAG_IO
DIAG(F("PCA9685 Configure VPIN:%d Apos:%d Ipos:%d Profile:%d Duration:%d state:%d"), DIAG(F("PCA9685 Configure VPIN:%u Apos:%d Ipos:%d Profile:%d Duration:%d state:%d"),
vpin, params[0], params[1], params[2], params[3], params[4]); vpin, params[0], params[1], params[2], params[3], params[4]);
#endif #endif
@@ -117,8 +117,8 @@ void PCA9685::_begin() {
// Device-specific write function, invoked from IODevice::write(). // Device-specific write function, invoked from IODevice::write().
// For this function, the configured profile is used. // For this function, the configured profile is used.
void PCA9685::_write(VPIN vpin, int value) { void PCA9685::_write(VPIN vpin, int value) {
#if DIAG_IO >= 3 #ifdef DIAG_IO
DIAG(F("PCA9685 Write Vpin:%d Value:%d"), vpin, value); DIAG(F("PCA9685 Write VPIN:%u Value:%d"), vpin, value);
#endif #endif
int pin = vpin - _firstVpin; int pin = vpin - _firstVpin;
if (value) value = 1; if (value) value = 1;
@@ -144,8 +144,8 @@ void PCA9685::_write(VPIN vpin, int value) {
// 4 (Bounce) Servo 'bounces' at extremes. // 4 (Bounce) Servo 'bounces' at extremes.
// //
void PCA9685::_writeAnalogue(VPIN vpin, int value, uint8_t profile, uint16_t duration) { void PCA9685::_writeAnalogue(VPIN vpin, int value, uint8_t profile, uint16_t duration) {
#if DIAG_IO >= 3 #ifdef DIAG_IO
DIAG(F("PCA9685 WriteAnalogue Vpin:%d Value:%d Profile:%d Duration:%d %S"), DIAG(F("PCA9685 WriteAnalogue VPIN:%u Value:%d Profile:%d Duration:%d %S"),
vpin, value, profile, duration, _deviceState == DEVSTATE_FAILED?F("DEVSTATE_FAILED"):F("")); vpin, value, profile, duration, _deviceState == DEVSTATE_FAILED?F("DEVSTATE_FAILED"):F(""));
#endif #endif
if (_deviceState == DEVSTATE_FAILED) return; if (_deviceState == DEVSTATE_FAILED) return;
@@ -262,7 +262,7 @@ void PCA9685::writeDevice(uint8_t pin, int value) {
// Display details of this device. // Display details of this device.
void PCA9685::_display() { void PCA9685::_display() {
DIAG(F("PCA9685 I2C:%s Configured on Vpins:%d-%d %S"), _I2CAddress.toString(), (int)_firstVpin, DIAG(F("PCA9685 I2C:%s Configured on Vpins:%u-%u %S"), _I2CAddress.toString(), (int)_firstVpin,
(int)_firstVpin+_nPins-1, (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F("")); (int)_firstVpin+_nPins-1, (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F(""));
} }

View File

@@ -120,8 +120,8 @@ private:
// //
void _writeAnalogue(VPIN vpin, int value, uint8_t param1, uint16_t param2) override { void _writeAnalogue(VPIN vpin, int value, uint8_t param1, uint16_t param2) override {
(void)param1; (void)param2; // suppress compiler warning (void)param1; (void)param2; // suppress compiler warning
#if DIAG_IO >= 3 #ifdef DIAG_IO
DIAG(F("PCA9685pwm WriteAnalogue Vpin:%d Value:%d %S"), DIAG(F("PCA9685pwm WriteAnalogue VPIN:%u Value:%d %S"),
vpin, value, _deviceState == DEVSTATE_FAILED?F("DEVSTATE_FAILED"):F("")); vpin, value, _deviceState == DEVSTATE_FAILED?F("DEVSTATE_FAILED"):F(""));
#endif #endif
if (_deviceState == DEVSTATE_FAILED) return; if (_deviceState == DEVSTATE_FAILED) return;
@@ -134,14 +134,14 @@ private:
// Display details of this device. // Display details of this device.
void _display() override { void _display() override {
DIAG(F("PCA9685pwm I2C:%s Configured on Vpins:%d-%d %S"), _I2CAddress.toString(), (int)_firstVpin, DIAG(F("PCA9685pwm I2C:%s Configured on Vpins:%u-%u %S"), _I2CAddress.toString(), (int)_firstVpin,
(int)_firstVpin+_nPins-1, (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F("")); (int)_firstVpin+_nPins-1, (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F(""));
} }
// writeDevice (helper function) takes a pin in range 0 to _nPins-1 within the device, and a value // writeDevice (helper function) takes a pin in range 0 to _nPins-1 within the device, and a value
// between 0 and 4095 for the PWM mark-to-period ratio, with 4095 being 100%. // between 0 and 4095 for the PWM mark-to-period ratio, with 4095 being 100%.
void writeDevice(uint8_t pin, int value) { void writeDevice(uint8_t pin, int value) {
#if DIAG_IO >= 3 #ifdef DIAG_IO
DIAG(F("PCA9685pwm I2C:%s WriteDevice Pin:%d Value:%d"), _I2CAddress.toString(), pin, value); DIAG(F("PCA9685pwm I2C:%s WriteDevice Pin:%d Value:%d"), _I2CAddress.toString(), pin, value);
#endif #endif
// Wait for previous request to complete // Wait for previous request to complete

View File

@@ -98,13 +98,14 @@ private:
void _write(VPIN vpin, int value) override { void _write(VPIN vpin, int value) override {
if (vpin == _firstVpin + 1) { if (vpin == _firstVpin + 1) {
byte _feedbackBuffer[2] = {RE_OP, value}; if (value != 0) value = 0x01;
byte _feedbackBuffer[2] = {RE_OP, (byte)value};
I2CManager.write(_I2CAddress, _feedbackBuffer, 2); I2CManager.write(_I2CAddress, _feedbackBuffer, 2);
} }
} }
void _display() override { void _display() override {
DIAG(F("Rotary Encoder I2C:%s v%d.%d.%d Configured on Vpin:%d-%d %S"), _I2CAddress.toString(), _majorVer, _minorVer, _patchVer, DIAG(F("Rotary Encoder I2C:%s v%d.%d.%d Configured on VPIN:%u-%d %S"), _I2CAddress.toString(), _majorVer, _minorVer, _patchVer,
(int)_firstVpin, _firstVpin+_nPins-1, (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F("")); (int)_firstVpin, _firstVpin+_nPins-1, (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F(""));
} }

View File

@@ -98,7 +98,7 @@ private:
if (configType != CONFIGURE_SERVO) return false; if (configType != CONFIGURE_SERVO) return false;
if (paramCount != 5) return false; if (paramCount != 5) return false;
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("Servo: Configure VPIN:%d Apos:%d Ipos:%d Profile:%d Duration:%d state:%d"), DIAG(F("Servo: Configure VPIN:%u Apos:%d Ipos:%d Profile:%d Duration:%d state:%d"),
vpin, params[0], params[1], params[2], params[3], params[4]); vpin, params[0], params[1], params[2], params[3], params[4]);
#endif #endif
@@ -140,12 +140,12 @@ private:
// Get reference to slave device. // Get reference to slave device.
_slaveDevice = findDevice(_firstSlavePin); _slaveDevice = findDevice(_firstSlavePin);
if (!_slaveDevice) { if (!_slaveDevice) {
DIAG(F("Servo: Slave device not found on pins %d-%d"), DIAG(F("Servo: Slave device not found on Vpins %u-%u"),
_firstSlavePin, _firstSlavePin+_nPins-1); _firstSlavePin, _firstSlavePin+_nPins-1);
_deviceState = DEVSTATE_FAILED; _deviceState = DEVSTATE_FAILED;
} }
if (_slaveDevice != findDevice(_firstSlavePin+_nPins-1)) { if (_slaveDevice != findDevice(_firstSlavePin+_nPins-1)) {
DIAG(F("Servo: Slave device does not cover all pins %d-%d"), DIAG(F("Servo: Slave device does not cover all Vpins %u-%u"),
_firstSlavePin, _firstSlavePin+_nPins-1); _firstSlavePin, _firstSlavePin+_nPins-1);
_deviceState = DEVSTATE_FAILED; _deviceState = DEVSTATE_FAILED;
} }
@@ -165,7 +165,7 @@ private:
void _write(VPIN vpin, int value) override { void _write(VPIN vpin, int value) override {
if (_deviceState == DEVSTATE_FAILED) return; if (_deviceState == DEVSTATE_FAILED) return;
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("Servo Write Vpin:%d Value:%d"), vpin, value); DIAG(F("Servo Write VPIN:%u Value:%d"), vpin, value);
#endif #endif
int pin = vpin - _firstVpin; int pin = vpin - _firstVpin;
if (value) value = 1; if (value) value = 1;
@@ -193,7 +193,7 @@ private:
// //
void _writeAnalogue(VPIN vpin, int value, uint8_t profile, uint16_t duration) override { void _writeAnalogue(VPIN vpin, int value, uint8_t profile, uint16_t duration) override {
#ifdef DIAG_IO #ifdef DIAG_IO
DIAG(F("Servo: WriteAnalogue Vpin:%d Value:%d Profile:%d Duration:%d %S"), DIAG(F("Servo: WriteAnalogue VPIN:%u Value:%d Profile:%d Duration:%d %S"),
vpin, value, profile, duration, _deviceState == DEVSTATE_FAILED?F("DEVSTATE_FAILED"):F("")); vpin, value, profile, duration, _deviceState == DEVSTATE_FAILED?F("DEVSTATE_FAILED"):F(""));
#endif #endif
if (_deviceState == DEVSTATE_FAILED) return; if (_deviceState == DEVSTATE_FAILED) return;
@@ -288,7 +288,7 @@ private:
// Display details of this device. // Display details of this device.
void _display() override { void _display() override {
DIAG(F("Servo Configured on Vpins:%d-%d, slave pins:%d-%d %S"), DIAG(F("Servo Configured on Vpins:%u-%u, slave pins:%d-%d %S"),
(int)_firstVpin, (int)_firstVpin+_nPins-1, (int)_firstVpin, (int)_firstVpin+_nPins-1,
(int)_firstSlavePin, (int)_firstSlavePin+_nPins-1, (int)_firstSlavePin, (int)_firstSlavePin+_nPins-1,
(_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F("")); (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F(""));

134
IO_TouchKeypad.h Normal file
View File

@@ -0,0 +1,134 @@
/*
* © 2023, Neil McKechnie. All rights reserved.
*
* This file is part of DCC++EX API
*
* 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/>.
*/
/*
* Driver for capacitative touch-pad based on the TTP229-B chip with serial
* (not I2C) output. The touchpad has 16 separate pads in a 4x4 matrix,
* numbered 1-16. The communications with the pad are via a clock signal sent
* from the controller to the device, and a data signal sent back by the device.
* The pins clockPin and dataPin must be local pins, not external (GPIO Expander)
* pins.
*
* To use,
* TouchKeypad::create(firstVpin, 16, clockPin, dataPin);
*
* NOTE: Most of these keypads ship with only 8 pads enabled. To enable all
* sixteen pads, locate the area of the board labelled P1 (four pairs of
* holes labelled 1 to 4 from the left); solder a jumper link between the pair
* labelled 3 (connected to pin TP2 on the chip). When this link is connected,
* the pins OUT1 to OUT8 are not used but all sixteen touch pads are operational.
*
* TODO: Allow a list of datapins to be provided so that multiple keypads can
* be read simultaneously by the one device driver and the one shared clock signal.
* As it stands, we can configure multiple driver instances, one for each keypad,
* and it will work fine. The clock will be driven to all devices but only one
* driver will be reading the responses from its corresponding device at a time.
*/
#ifndef IO_TOUCHKEYPAD_H
#define IO_TOUCHKEYPAD_H
#include "IODevice.h"
class TouchKeypad : public IODevice {
private:
// Here we define the device-specific variables.
uint16_t _inputStates = 0;
VPIN _clockPin;
VPIN _dataPin;
public:
// Static function to handle create calls.
static void create(VPIN firstVpin, int nPins, VPIN clockPin, VPIN dataPin) {
if (checkNoOverlap(firstVpin,nPins)) new TouchKeypad(firstVpin, nPins, clockPin, dataPin);
}
protected:
// Constructor.
TouchKeypad(VPIN firstVpin, int nPins, VPIN clockPin, VPIN dataPin) {
_firstVpin = firstVpin;
_nPins = (nPins > 16) ? 16 : nPins; // Maximum of 16 pads per device
_clockPin = clockPin;
_dataPin = dataPin;
addDevice(this);
}
// Device-specific initialisation
void _begin() override {
#if defined(DIAG_IO)
_display();
#endif
// Set clock pin as output, initially high, and data pin as input.
// Enable pullup on the input so that the default (not connected) state is
// 'keypad not pressed'.
ArduinoPins::fastWriteDigital(_clockPin, 1);
pinMode(_clockPin, OUTPUT);
pinMode(_dataPin, INPUT_PULLUP); // Force defined state when no connection
}
// Device-specific read function.
int _read(VPIN vpin) {
if (vpin < _firstVpin || vpin >= _firstVpin + _nPins) return 0;
// Return a value for the specified vpin.
return _inputStates & (1<<(vpin-_firstVpin)) ? 1 : 0;
}
// Loop function to do background scanning of the keyboard.
// The TTP229 device requires clock pulses to be sent to it,
// and the data bits can be read on the rising edge of the clock.
// By default the clock and data are inverted (active-low).
// A gap of more than 2ms is advised between successive read
// cycles, we wait for 100ms between reads of the keyboard as this
// provide a good enough response time.
// Maximum clock frequency is 512kHz, so put a 1us delay
// between clock transitions.
//
void _loop(unsigned long currentMicros) {
// Clock 16 bits from the device
uint16_t data = 0, maskBit = 0x01;
for (uint8_t pad=0; pad<16; pad++) {
ArduinoPins::fastWriteDigital(_clockPin, 0);
delayMicroseconds(1);
ArduinoPins::fastWriteDigital(_clockPin, 1);
data |= (ArduinoPins::fastReadDigital(_dataPin) ? 0 : maskBit);
maskBit <<= 1;
delayMicroseconds(1);
}
_inputStates = data;
#ifdef DIAG_IO
static uint16_t lastData = 0;
if (data != lastData) DIAG(F("KeyPad: %x"), data);
lastData = data;
#endif
delayUntil(currentMicros + 100000); // read every 100ms
}
// Display information about the device, and perhaps its current condition (e.g. active, disabled etc).
void _display() {
DIAG(F("TouchKeypad Configured on Vpins:%u-%u SCL=%d SDO=%d"), (int)_firstVpin,
(int)_firstVpin+_nPins-1, _clockPin, _dataPin);
}
};
#endif // IO_TOUCHKEYPAD_H

View File

@@ -319,7 +319,7 @@ protected:
} }
void _display() override { void _display() override {
DIAG(F("VL53L0X I2C:%s Configured on Vpins:%d-%d On:%dmm Off:%dmm %S"), DIAG(F("VL53L0X I2C:%s Configured on Vpins:%u-%u On:%dmm Off:%dmm %S"),
_I2CAddress.toString(), _firstVpin, _firstVpin+_nPins-1, _onThreshold, _offThreshold, _I2CAddress.toString(), _firstVpin, _firstVpin+_nPins-1, _onThreshold, _offThreshold,
(_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F("")); (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F(""));
} }

View File

@@ -55,6 +55,7 @@ public:
pinMode(_clockPin,OUTPUT); pinMode(_clockPin,OUTPUT);
pinMode(_dataPin,_pinMap?INPUT_PULLUP:OUTPUT); pinMode(_dataPin,_pinMap?INPUT_PULLUP:OUTPUT);
_display(); _display();
if (!_pinMap) _loopOutput();
} }
// loop called by HAL supervisor // loop called by HAL supervisor
@@ -121,7 +122,7 @@ void _loopOutput() {
} }
void _display() override { void _display() override {
DIAG(F("IO_duinoNodes %SPUT Configured on VPins:%d-%d shift=%d"), DIAG(F("IO_duinoNodes %SPUT Configured on Vpins:%u-%u shift=%d"),
_pinMap?F("IN"):F("OUT"), _pinMap?F("IN"):F("OUT"),
(int)_firstVpin, (int)_firstVpin,
(int)_firstVpin+_nPins-1, _nShiftBytes*8); (int)_firstVpin+_nPins-1, _nShiftBytes*8);

View File

@@ -75,6 +75,23 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
dualSignal=true; dualSignal=true;
getFastPin(F("SIG2"),signalPin2,fastSignalPin2); getFastPin(F("SIG2"),signalPin2,fastSignalPin2);
pinMode(signalPin2, OUTPUT); pinMode(signalPin2, OUTPUT);
fastSignalPin2.shadowinout = NULL;
if (HAVE_PORTA(fastSignalPin2.inout == &PORTA)) {
DIAG(F("Found PORTA pin %d"),signalPin2);
fastSignalPin2.shadowinout = fastSignalPin2.inout;
fastSignalPin2.inout = &shadowPORTA;
}
if (HAVE_PORTB(fastSignalPin2.inout == &PORTB)) {
DIAG(F("Found PORTB pin %d"),signalPin2);
fastSignalPin2.shadowinout = fastSignalPin2.inout;
fastSignalPin2.inout = &shadowPORTB;
}
if (HAVE_PORTC(fastSignalPin2.inout == &PORTC)) {
DIAG(F("Found PORTC pin %d"),signalPin2);
fastSignalPin2.shadowinout = fastSignalPin2.inout;
fastSignalPin2.inout = &shadowPORTC;
}
} }
else dualSignal=false; else dualSignal=false;
@@ -90,9 +107,8 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
else brakePin=UNUSED_PIN; else brakePin=UNUSED_PIN;
currentPin=current_pin; currentPin=current_pin;
if (currentPin!=UNUSED_PIN) { if (currentPin!=UNUSED_PIN) ADCee::init(currentPin);
senseOffset = ADCee::init(currentPin); senseOffset=0; // value can not be obtained until waveform is activated
}
faultPin=fault_pin; faultPin=fault_pin;
if (faultPin != UNUSED_PIN) { if (faultPin != UNUSED_PIN) {
@@ -121,8 +137,7 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
if (currentPin==UNUSED_PIN) if (currentPin==UNUSED_PIN)
DIAG(F("** WARNING ** No current or short detection")); DIAG(F("** WARNING ** No current or short detection"));
else { else {
DIAG(F("CurrentPin=A%d, Offset=%d, TripValue=%d"), DIAG(F("Track %c, TripValue=%d"), trackLetter, rawCurrentTripValue);
currentPin-A0, senseOffset,rawCurrentTripValue);
// self testing diagnostic for the non-float converters... may be removed when happy // self testing diagnostic for the non-float converters... may be removed when happy
// DIAG(F("senseFactorInternal=%d raw2mA(1000)=%d mA2Raw(1000)=%d"), // DIAG(F("senseFactorInternal=%d raw2mA(1000)=%d mA2Raw(1000)=%d"),
@@ -144,6 +159,12 @@ bool MotorDriver::isPWMCapable() {
void MotorDriver::setPower(POWERMODE mode) { void MotorDriver::setPower(POWERMODE mode) {
bool on=mode==POWERMODE::ON; bool on=mode==POWERMODE::ON;
if (on) { if (on) {
// when switching a track On, we need to check the crrentOffset with the pin OFF
if (powerMode==POWERMODE::OFF && currentPin!=UNUSED_PIN) {
senseOffset = ADCee::read(currentPin);
DIAG(F("Track %c sensOffset=%d"),trackLetter,senseOffset);
}
IODevice::write(powerPin,invertPower ? LOW : HIGH); IODevice::write(powerPin,invertPower ? LOW : HIGH);
if (isProgTrack) if (isProgTrack)
DCCWaveform::progTrack.clearResets(); DCCWaveform::progTrack.clearResets();
@@ -234,7 +255,7 @@ void MotorDriver::startCurrentFromHW() {
#if defined(ARDUINO_ARCH_ESP32) #if defined(ARDUINO_ARCH_ESP32)
uint16_t taurustones[28] = { 165, 175, 196, 220, uint16_t taurustones[28] = { 165, 175, 196, 220,
247, 262, 294, 330, 247, 262, 294, 330,
249, 392, 440, 494, 349, 392, 440, 494,
523, 587, 659, 698, 523, 587, 659, 698,
494, 440, 392, 249, 494, 440, 392, 249,
330, 284, 262, 247, 330, 284, 262, 247,

View File

@@ -182,11 +182,15 @@ class MotorDriver {
isProgTrack = on; isProgTrack = on;
} }
void checkPowerOverload(bool useProgLimit, byte trackno); void checkPowerOverload(bool useProgLimit, byte trackno);
inline void setTrackLetter(char c) {
trackLetter = c;
};
#ifdef ANALOG_READ_INTERRUPT #ifdef ANALOG_READ_INTERRUPT
bool sampleCurrentFromHW(); bool sampleCurrentFromHW();
void startCurrentFromHW(); void startCurrentFromHW();
#endif #endif
private: private:
char trackLetter = '?';
bool isProgTrack = false; // tells us if this is a prog track bool isProgTrack = false; // tells us if this is a prog track
void getFastPin(const FSH* type,int pin, bool input, FASTPIN & result); void getFastPin(const FSH* type,int pin, bool input, FASTPIN & result);
void getFastPin(const FSH* type,int pin, FASTPIN & result) { void getFastPin(const FSH* type,int pin, FASTPIN & result) {

View File

@@ -73,12 +73,12 @@
#elif defined(ARDUINO_ARCH_ESP32) #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 eiter the
// 3.3V compatible R3 version or it has to be modified to not supply more than 3.3V to 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 A4 and A5 as A0 and A1 are wired in a way so that // 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 // 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. // actual GPIO numbers. In comments the numbers the pins have on an Uno.
#define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"), \ #define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"), \
new MotorDriver(25/* 3*/, 19/*12*/, UNUSED_PIN, 13/*9*/, 36/*A4*/, 0.70, 1500, UNUSED_PIN), \ 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*/, 39/*A5*/, 0.70, 1500, UNUSED_PIN) new MotorDriver(23/*11*/, 18/*13*/, UNUSED_PIN, 12/*8*/, 34/*A3*/, 0.70, 1500, UNUSED_PIN)
#else #else
// STANDARD shield on any Arduino Uno or Mega compatible with the original specification. // STANDARD shield on any Arduino Uno or Mega compatible with the original specification.

197
Release_Notes/CommandRef.md Normal file
View File

@@ -0,0 +1,197 @@
This file is being used to consolidate the command reference information.
General points:
- Commands below have a single character opcode and parameters.
Even <JA> is actually read as <J A>
- Keyword parameters are shown in upper case but may be entered in mixed case.
- value parameters are decimal numeric (unless otherwise noted)
- [something] indicates its optional.
- Not all commands have a response, and broadcasts mean that not all responses come from the last commands that you have issued.
Startup status
<s> Return status like
<iDCC-EX V-4.2.22 / MEGA / STANDARD_MOTOR_SHIELD G-devel-202302281422Z>
also returns defined turnout list:
<H id 1|0> 1=thrown
Track power management. After power commands a power state is broadcast to all throttles.
<1> Power on all
<1 MAIN|PROG|JOIN> Power on MAIN or PROG track
<1 JOIN> Power on MAIN and PROG track but send main track data on both.
<0> Power off all tracks
<0 MAIN|PROG> Power off main or prog track
Basic manual loco control
<t locoid speed direction> Throttle loco.
speed in JMRI-form (-1=ESTOP, 0=STOP, 1..126 = DCC speeds 2..127)
direction 1=forward, 0=reverse
For response see broadcast <l>
<F locoid function 1|0> Set loco function 1=ON, 0-OFF
For response see broadcast <l>
<!> emergency stop all locos
<T id 0|1|T|C> Control turnout id, 0=C=Closed, 1=T=Thrown
response broadcast <H id 0|1>
DCC accessory control
<a address subaddress activate [onoff]>
<a linearaddress activate>
Turnout definition
Note: Turnouts are best defined in myAutomation.h where a turnout description can also be provided ( refer to EXRAIL documentation) or by using these commands in a mySetup.h file.
<T id SERVO vpin thrown closed profile>
<T id VPIN vpin>
<T id DCC addr subaddr>
<T id DCC linearaddr>
Valid commands respond with <O>
Direct pin manipulation (replaces <Z commands, no predefinition required)
<z vpin> Set pin HIGH
<z -vpin> Set pin LOW
<z vpin value> Set pin analog value
<z vpin value profile> Set pin analog with profile
<z vpin value profile duration> set pin analog with profile and value
Sensors (Used by JMRI, not required by EXRAIL)
<S id vpin pullup> define a sensor to be monitored.
Responses <Q id> and <q id> as sensor changes
Decoder programming - main track
<w cab cv value> POM write value to cv on loco
<b cab cv bit value> POM write bit to cv on loco
Decoder Programming - prog track
<W cabid> Clear consist and write new cab id (includes long/short settings)
Responds <W cabid> or <W -1> for error
<W cv value> Write value to cv
<V cv predictedValue> Read cv value, much faster if prediction is correct.
<V cv bit predictedValue> Read CV bit
<R> Read drive-away loco id. (May be a consist id)
<D ACK ON|OFF>
<D ACK LIMIT|MIN|MAX|RETRY value>
<D PROGBOOST>
Advanced DCC control
<M packet.... >
<P packet ...>
<f map1 map2 [map3]>
<#>
<->
<- cabid>
<D CABS>
<D SPEED28>
<D SPEED128>
EEPROM commands
These commands exist for
backwards JMRI compatibility.
You are strongly discouraged from maintaining your configuration settings in EEPROM.
<E>
<e>
<D EEPROM>
<T>
<T id>
<S>
<S id>
<Z>
<Z id>
Diagnostic commands
<D CMD ON|OFF>
<D WIFI ON|OFF>
<D ETHERNET ON|OFF>
<D WIT ON|OFF>
<D LCN ON|OFF>
<D EXRAIL ON|OFF>
<D RESET>
<D SERVO|ANOUT vpin position [profile]>
<D ANIN vpin>
<D HAL SHOW>
<D HAL RESET>
<+ cmd>
<+>
<Q>
User defined filter commands
<U ....>
<u ....>
Track Management
<=>
<= track DCC|PROG|OFF>
<= track DC|DCX cabid>
<JG>
<JI>
Turntable interface
<D TT vpin steps [activity]>
Fast clock interface
<JC>
<JC mins rate>
Advanced Throttle access to features
<t cab>
<JA>
<JA id>
<JR>
<JR id>
<JT>
<JT id>
*******************
EXRAIL Commands
*******************
</>
</PAUSE>
</RESUME>
</START cab sequence>
</START sequence>
</KILL taskid>
</KILL ALL>
</RESERVE|FREE blockid>
</LATCH|UNLATCH latchid>
</RED|AMBER|GREEN signalid>
Obsolete commands/formats
<c>
<t ignored cab speed direction>
<T id vpin thrown closed>
<T id addr subaddr>
<B cv bit value obsolete obsolete>
<R cv obsolete obsolete>
<W cv value obsolete obsolete>
<R cv> V command is much faster if prediction is correct.
<B cv bit value> V command is much faster if prediction is correct.
<Z id vpin active> (use <z) Define an output pin that JMRI can set by id
<Z id activate> (use <z) Activate an output pin by id
Broadcast responses
Note: broadcasts are sent to all throttles when appropriate (usually because something has changed)
<p0>
<p1>
<p1 MAIN|PROG|JOIN>
<l cab slot dccspeed functionmap>
<H id 1|0>
<jC mmmm speed>
Diagnostic responses
These are not meant to be software readable. They contain diagnostic information for programmers to identify issues.
<X>
<* ... *>

View File

@@ -236,11 +236,6 @@ void SSD1306AsciiWire::setRowNative(uint8_t line) {
size_t SSD1306AsciiWire::writeNative(uint8_t ch) { size_t SSD1306AsciiWire::writeNative(uint8_t ch) {
const uint8_t* base = m_font; const uint8_t* base = m_font;
if (ch < m_fontFirstChar || ch >= (m_fontFirstChar + m_fontCharCount))
return 0;
// Check if character would be partly or wholly off the display
if (m_col + fontWidth > m_displayWidth)
return 0;
#if defined(NOLOWERCASE) #if defined(NOLOWERCASE)
// Adjust if lowercase is missing // Adjust if lowercase is missing
if (ch >= 'a') { if (ch >= 'a') {
@@ -250,6 +245,12 @@ size_t SSD1306AsciiWire::writeNative(uint8_t ch) {
ch -= 26; // Allow for missing lowercase letters ch -= 26; // Allow for missing lowercase letters
} }
#endif #endif
if (ch < m_fontFirstChar || ch >= (m_fontFirstChar + m_fontCharCount))
return 0;
// Check if character would be partly or wholly off the display
if (m_col + fontWidth > m_displayWidth)
return 0;
ch -= m_fontFirstChar; ch -= m_fontFirstChar;
base += fontWidth * ch; base += fontWidth * ch;
// Before using buffer, wait for last request to complete // Before using buffer, wait for last request to complete
@@ -406,8 +407,8 @@ const uint8_t FLASH SSD1306AsciiWire::System6x8[] = {
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x38, 0x44, 0xc6, 0x44, 0x20, 0x00, // cent 0x9b
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x44, 0x6e, 0x59, 0x49, 0x62, 0x00, // £ 0x9c
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented
@@ -425,27 +426,27 @@ const uint8_t FLASH SSD1306AsciiWire::System6x8[] = {
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x10, 0x28, 0x54, 0x28, 0x44, 0x00, // <<
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x44, 0x28, 0x54, 0x28, 0x10, 0x00, // >>
// Extended characters 176-180 // Extended characters 176-180
0x92, 0x00, 0x49, 0x00, 0x24, 0x00, // Light grey 0xb0 0x92, 0x00, 0x49, 0x00, 0x24, 0x00, // Light grey 0xb0
0xcc, 0x55, 0xcc, 0x55, 0xcc, 0x55, // Mid grey 0xb1 0xaa, 0x44, 0xaa, 0x11, 0xaa, 0x55, // Mid grey 0xb1
0x6a, 0xff, 0xb6, 0xff, 0xdb, 0xff, // Dark grey 0xb2 0x6d, 0xff, 0xb6, 0xff, 0xdb, 0xff, // Dark grey 0xb2
0x00, 0x00, 0x00, 0xff, 0x00, 0x00, // Vertical line 0xb3 0x00, 0x00, 0x00, 0xff, 0x00, 0x00, // Vertical line 0xb3
0x08, 0x08, 0x08, 0xff, 0x00, 0x00, // Vertical line with left spur 0xb4 0x08, 0x08, 0x08, 0xff, 0x00, 0x00, // Vertical line with left spur 0xb4
0x14, 0x14, 0xfe, 0x00, 0xff, 0x00, // Vertical line with double left spur 0xb9 0x14, 0x14, 0x14, 0xff, 0x00, 0x00, // Vertical line with double left spur 0xb5
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented Double vertical line with single left spur 0x08, 0x08, 0xff, 0x00, 0xff, 0x00, // Double vertical line with single left spur
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x08, 0x08, 0xf8, 0x08, 0xf8, 0x00, // Top right corner, single horiz, double vert
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x14, 0x14, 0x14, 0xfc, 0x00, 0x00, // Top right corner, double horiz, single vert
// Extended characters 185-190 // Extended characters 185-190
0x28, 0x28, 0xef, 0x00, 0xff, 0x00, // Double vertical line with double left spur 0xb9 0x14, 0x14, 0xf7, 0x00, 0xff, 0x00, // Double vertical line with double left spur 0xb9
0x00, 0x00, 0xff, 0x00, 0xff, 0x00, // Double vertical line 0xba 0x00, 0x00, 0xff, 0x00, 0xff, 0x00, // Double vertical line 0xba
0x14, 0x14, 0xf4, 0x04, 0xfc, 0x00, // Double top right corner 0xbb 0x14, 0x14, 0xf4, 0x04, 0xfc, 0x00, // Double top right corner 0xbb
0x14, 0x14, 0x17, 0x10, 0x1f, 0x00, // Double bottom right corner 0xbc 0x14, 0x14, 0x17, 0x10, 0x1f, 0x00, // Double bottom right corner 0xbc
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0xbd 0x08, 0x08, 0x0f, 0x08, 0x0f, 0x00, // Bottom right corner, single horiz, double vert 0xbd
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0xbe 0x14, 0x14, 0x14, 0x1f, 0x00, 0x00, // Bottom right corner, double horiz, single vert 0xbe
// Extended characters 191-199 // Extended characters 191-199
0x08, 0x08, 0x08, 0xf8, 0x00, 0x00, // Top right corner 0xbf 0x08, 0x08, 0x08, 0xf8, 0x00, 0x00, // Top right corner 0xbf
@@ -455,8 +456,8 @@ const uint8_t FLASH SSD1306AsciiWire::System6x8[] = {
0x00, 0x00, 0x00, 0xff, 0x08, 0x08, // Vertical line with right spur 0xc3 0x00, 0x00, 0x00, 0xff, 0x08, 0x08, // Vertical line with right spur 0xc3
0x08, 0x08, 0x08, 0x08, 0x08, 0x08, // Horizontal line 0xc4 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, // Horizontal line 0xc4
0x08, 0x08, 0x08, 0xff, 0x08, 0x08, // Cross 0xc5 0x08, 0x08, 0x08, 0xff, 0x08, 0x08, // Cross 0xc5
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0xff, 0x14, 0x14, // Vertical line double right spur 0xc6
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0xff, 0x00, 0xff, 0x08, // Double vertical line single right spur 0xc7
// Extended characters 200-206 // Extended characters 200-206
0x00, 0x00, 0x1f, 0x10, 0x17, 0x14, // Double bottom left corner 0xc8 0x00, 0x00, 0x1f, 0x10, 0x17, 0x14, // Double bottom left corner 0xc8
@@ -467,16 +468,16 @@ const uint8_t FLASH SSD1306AsciiWire::System6x8[] = {
0x14, 0x14, 0x14, 0x14, 0x14, 0x14, // Double horizontal line 0xcd 0x14, 0x14, 0x14, 0x14, 0x14, 0x14, // Double horizontal line 0xcd
0x14, 0x14, 0xf7, 0x00, 0xf7, 0x14, // Double cross 0xce 0x14, 0x14, 0xf7, 0x00, 0xf7, 0x14, // Double cross 0xce
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x14, 0x14, 0x14, 0x17, 0x14, 0x14, // Double horizontal line single upward spur 0xcf
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0xd0 0x08, 0x08, 0x0f, 0x08, 0x0f, 0x08, // Horiz single line with double upward spur 0xd0
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x14, 0x14, 0x14, 0xf4, 0x14, 0x14, // Horiz double line with single downward spur 0xd1
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x08, 0x08, 0xf8, 0x08, 0xf8, 0x08, // Horiz single line with double downward spur 0xd2
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x0f, 0x08, 0x0f, 0x08, // Bottom left corner, double vert single horiz 0xd3
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x1f, 0x14, 0x14, // Bottom left corner, single vert double horiz 0xd4
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0xfc, 0x14, 0x14, // Top left corner, single vert double horiz 0xd5
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0xf8, 0x08, 0xf8, 0x08, // Top left corner, double vert single horiz 0xd6
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x08, 0x08, 0xff, 0x00, 0xff, 0x08, // Cross, double vert single horiz 0xd7
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x14, 0x14, 0x14, 0xf7, 0x14, 0x14, // Cross, single vert double horiz 0xd8
// Extended characters 217-223 // Extended characters 217-223
0x08, 0x08, 0x08, 0x0f, 0x00, 0x00, // Bottom right corner 0xd9 0x08, 0x08, 0x08, 0x0f, 0x00, 0x00, // Bottom right corner 0xd9
@@ -487,10 +488,10 @@ const uint8_t FLASH SSD1306AsciiWire::System6x8[] = {
0x00, 0x00, 0x00, 0xff, 0xff, 0xff, // Right half block 0xde 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, // Right half block 0xde
0x0f, 0x0f, 0x0f, 0x0f, 0x0f, 0x0f, // Top half block 0xdf 0x0f, 0x0f, 0x0f, 0x0f, 0x0f, 0x0f, // Top half block 0xdf
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0xe0 0xf0, 0xf0, 0xf0, 0x00, 0x00, 0x00, // Bottom Left block 0xe0
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0xf0, 0xf0, 0xf0, // Bottom Right block
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x0f, 0x0f, 0x0f, 0x00, 0x00, 0x00, // Top left block
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x0f, 0x0f, 0x0f, // Top right block 0xe3
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented
@@ -511,9 +512,8 @@ const uint8_t FLASH SSD1306AsciiWire::System6x8[] = {
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Not implemented
// Extended character 248 // Extended character 248
0x00, 0x06, 0x09, 0x09, 0x06, 0x00, // degree symbol 0xf8 0x00, 0x06, 0x09, 0x09, 0x06, 0x00 // degree symbol 0xf8
#endif #endif
0x00
}; };
const uint8_t SSD1306AsciiWire::m_fontCharCount = sizeof(System6x8) / 6; const uint8_t SSD1306AsciiWire::m_fontCharCount = sizeof(System6x8) / 6;

View File

@@ -25,6 +25,7 @@
#include "MotorDriver.h" #include "MotorDriver.h"
#include "DCCTimer.h" #include "DCCTimer.h"
#include "DIAG.h" #include "DIAG.h"
#include"CommandDistributor.h"
// Virtualised Motor shield multi-track hardware Interface // Virtualised Motor shield multi-track hardware Interface
#define FOR_EACH_TRACK(t) for (byte t=0;t<=lastTrack;t++) #define FOR_EACH_TRACK(t) for (byte t=0;t<=lastTrack;t++)
@@ -128,6 +129,7 @@ void TrackManager::addTrack(byte t, MotorDriver* driver) {
track[t]=driver; track[t]=driver;
if (driver) { if (driver) {
track[t]->setPower(POWERMODE::OFF); track[t]->setPower(POWERMODE::OFF);
track[t]->setTrackLetter('A'+t);
lastTrack=t; lastTrack=t;
} }
} }
@@ -203,6 +205,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
track[t]->setPower(POWERMODE::OFF); track[t]->setPower(POWERMODE::OFF);
trackMode[t]=TRACK_MODE_OFF; trackMode[t]=TRACK_MODE_OFF;
track[t]->makeProgTrack(false); // revoke prog track special handling track[t]->makeProgTrack(false); // revoke prog track special handling
streamTrackState(NULL,t);
} }
track[trackToSet]->makeProgTrack(true); // set for prog track special handling track[trackToSet]->makeProgTrack(true); // set for prog track special handling
} else { } else {
@@ -210,7 +213,8 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr
} }
trackMode[trackToSet]=mode; trackMode[trackToSet]=mode;
trackDCAddr[trackToSet]=dcAddr; trackDCAddr[trackToSet]=dcAddr;
streamTrackState(NULL,trackToSet);
// When a track is switched, we must clear any side effects of its previous // 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 dont move.
@@ -290,36 +294,7 @@ bool TrackManager::parseJ(Print *stream, int16_t params, int16_t p[])
if (params==0) { // <=> List track assignments if (params==0) { // <=> List track assignments
FOR_EACH_TRACK(t) FOR_EACH_TRACK(t)
if (track[t]!=NULL) { streamTrackState(stream,t);
StringFormatter::send(stream,F("<= %c "),'A'+t);
switch(trackMode[t]) {
case TRACK_MODE_MAIN:
StringFormatter::send(stream,F("MAIN"));
if (track[t]->trackPWM)
StringFormatter::send(stream,F("+"));
break;
case TRACK_MODE_PROG:
StringFormatter::send(stream,F("PROG"));
if (track[t]->trackPWM)
StringFormatter::send(stream,F("+"));
break;
case TRACK_MODE_OFF:
StringFormatter::send(stream,F("OFF"));
break;
case TRACK_MODE_EXT:
StringFormatter::send(stream,F("EXT"));
break;
case TRACK_MODE_DC:
StringFormatter::send(stream,F("DC %d"),trackDCAddr[t]);
break;
case TRACK_MODE_DCX:
StringFormatter::send(stream,F("DCX %d"),trackDCAddr[t]);
break;
default:
break; // unknown, dont care
}
StringFormatter::send(stream,F(">\n"));
}
return true; return true;
} }
@@ -349,6 +324,36 @@ bool TrackManager::parseJ(Print *stream, int16_t params, int16_t p[])
return false; return false;
} }
void TrackManager::streamTrackState(Print* stream, byte t) {
// null stream means send to commandDistributor for broadcast
if (track[t]==NULL) return;
auto format=F("");
switch(trackMode[t]) {
case TRACK_MODE_MAIN:
format=F("<= %c MAIN>\n");
break;
case TRACK_MODE_PROG:
format=F("<= %c PROG>\n");
break;
case TRACK_MODE_OFF:
format=F("<= %c OFF>\n");
break;
case TRACK_MODE_EXT:
format=F("<= %c EXT>\n");
break;
case TRACK_MODE_DC:
format=F("<= %c DC %d>\n");
break;
case TRACK_MODE_DCX:
format=F("<= %c DCX %d>\n");
break;
default:
break; // unknown, dont care
}
if (stream) StringFormatter::send(stream,format,'A'+t,trackDCAddr[t]);
else CommandDistributor::broadcastTrackState(format,'A'+t,trackDCAddr[t]);
}
byte TrackManager::nextCycleTrack=MAX_TRACKS; byte TrackManager::nextCycleTrack=MAX_TRACKS;
void TrackManager::loop() { void TrackManager::loop() {
@@ -423,7 +428,35 @@ POWERMODE TrackManager::getProgPower() {
return track[t]->getPower(); return track[t]->getPower();
return POWERMODE::OFF; return POWERMODE::OFF;
} }
void TrackManager::reportObsoleteCurrent(Print* stream) {
// This function is for backward JMRI compatibility only
// It reports the first track only, as main, regardless of track settings.
// <c MeterName value C/V unit min max res warn>
int maxCurrent=track[0]->raw2mA(track[0]->getRawCurrentTripValue());
StringFormatter::send(stream, F("<c CurrentMAIN %d C Milli 0 %d 1 %d>\n"),
track[0]->raw2mA(track[0]->getCurrentRaw(false)), maxCurrent, maxCurrent);
}
void TrackManager::reportCurrent(Print* stream) {
StringFormatter::send(stream,F("<jI"));
FOR_EACH_TRACK(t) {
StringFormatter::send(stream, F(" %d"),
(track[t]->getPower()==POWERMODE::OVERLOAD) ? -1 :
track[t]->raw2mA(track[t]->getCurrentRaw(false)));
}
StringFormatter::send(stream,F(">\n"));
}
void TrackManager::reportGauges(Print* stream) {
StringFormatter::send(stream,F("<jG"));
FOR_EACH_TRACK(t) {
StringFormatter::send(stream, F(" %d"),
track[t]->raw2mA(track[t]->getRawCurrentTripValue()));
}
StringFormatter::send(stream,F(">\n"));
}
void TrackManager::setJoinRelayPin(byte joinRelayPin) { void TrackManager::setJoinRelayPin(byte joinRelayPin) {
joinRelay=joinRelayPin; joinRelay=joinRelayPin;
if (joinRelay!=UNUSED_PIN) { if (joinRelay!=UNUSED_PIN) {

View File

@@ -77,6 +77,11 @@ class TrackManager {
static bool isJoined() { return progTrackSyncMain;} static bool isJoined() { return progTrackSyncMain;}
static void setJoinRelayPin(byte joinRelayPin); static void setJoinRelayPin(byte joinRelayPin);
static void sampleCurrent(); static void sampleCurrent();
static void reportGauges(Print* stream);
static void reportCurrent(Print* stream);
static void reportObsoleteCurrent(Print* stream);
static void streamTrackState(Print* stream, byte t);
static int16_t joinRelay; static int16_t joinRelay;
static bool progTrackSyncMain; // true when prog track is a siding switched to main static bool progTrackSyncMain; // true when prog track is a siding switched to main
static bool progTrackBoosted; // true when prog track is not current limited static bool progTrackBoosted; // true when prog track is not current limited

View File

@@ -110,49 +110,40 @@
/* static */ bool Turnout::setClosedStateOnly(uint16_t id, bool closeFlag) { /* static */ bool Turnout::setClosedStateOnly(uint16_t id, bool closeFlag) {
Turnout *tt = get(id); Turnout *tt = get(id);
if (!tt) return false; if (!tt) return false;
tt->_turnoutData.closed = closeFlag;
// I know it says setClosedStateOnly, but we need to tell others // I know it says setClosedStateOnly, but we need to tell others
// that the state has changed too. // that the state has changed too. But we only broadcast if there
#if defined(EXRAIL_ACTIVE) // really has been a change.
RMFT2::turnoutEvent(id, closeFlag); if (tt->_turnoutData.closed != closeFlag) {
#endif tt->_turnoutData.closed = closeFlag;
CommandDistributor::broadcastTurnout(id, closeFlag);
CommandDistributor::broadcastTurnout(id, closeFlag); }
#if defined(EXRAIL_ACTIVE)
RMFT2::turnoutEvent(id, closeFlag);
#endif
return true; return true;
} }
#define DIAG_IO
// Static setClosed function is invoked from close(), throw() etc. to perform the // Static setClosed function is invoked from close(), throw() etc. to perform the
// common parts of the turnout operation. Code which is specific to a turnout // common parts of the turnout operation. Code which is specific to a turnout
// type should be placed in the virtual function setClosedInternal(bool) which is // type should be placed in the virtual function setClosedInternal(bool) which is
// called from here. // called from here.
/* static */ bool Turnout::setClosed(uint16_t id, bool closeFlag) { /* static */ bool Turnout::setClosed(uint16_t id, bool closeFlag) {
#if defined(DIAG_IO) #if defined(DIAG_IO)
if (closeFlag) DIAG(F("Turnout(%d,%c)"), id, closeFlag ? 'c':'t');
DIAG(F("Turnout::close(%d)"), id); #endif
else
DIAG(F("Turnout::throw(%d)"), id);
#endif
Turnout *tt = Turnout::get(id); Turnout *tt = Turnout::get(id);
if (!tt) return false; if (!tt) return false;
bool ok = tt->setClosedInternal(closeFlag); bool ok = tt->setClosedInternal(closeFlag);
if (ok) { if (ok) {
tt->setClosedStateOnly(id, closeFlag);
#ifndef DISABLE_EEPROM #ifndef DISABLE_EEPROM
// Write byte containing new closed/thrown state to EEPROM if required. Note that eepromAddress // Write byte containing new closed/thrown state to EEPROM if required. Note that eepromAddress
// is always zero for LCN turnouts. // is always zero for LCN turnouts.
if (EEStore::eeStore->data.nTurnouts > 0 && tt->_eepromAddress > 0) if (EEStore::eeStore->data.nTurnouts > 0 && tt->_eepromAddress > 0)
EEPROM.put(tt->_eepromAddress, tt->_turnoutData.flags); EEPROM.put(tt->_eepromAddress, tt->_turnoutData.flags);
#endif #endif
#if defined(EXRAIL_ACTIVE)
RMFT2::turnoutEvent(id, closeFlag);
#endif
// Send message to JMRI etc.
CommandDistributor::broadcastTurnout(id, closeFlag);
} }
return ok; return ok;
} }
@@ -298,7 +289,6 @@
#ifndef IO_NO_HAL #ifndef IO_NO_HAL
IODevice::writeAnalogue(_servoTurnoutData.vpin, IODevice::writeAnalogue(_servoTurnoutData.vpin,
close ? _servoTurnoutData.closedPosition : _servoTurnoutData.thrownPosition, _servoTurnoutData.profile); close ? _servoTurnoutData.closedPosition : _servoTurnoutData.thrownPosition, _servoTurnoutData.profile);
_turnoutData.closed = close;
#else #else
(void)close; // avoid compiler warnings (void)close; // avoid compiler warnings
#endif #endif
@@ -396,7 +386,6 @@
// and Close writes a 0. // and Close writes a 0.
// RCN-213 specifies that Throw is 0 and Close is 1. // RCN-213 specifies that Throw is 0 and Close is 1.
DCC::setAccessory(_dccTurnoutData.address, _dccTurnoutData.subAddress, close ^ !rcn213Compliant); DCC::setAccessory(_dccTurnoutData.address, _dccTurnoutData.subAddress, close ^ !rcn213Compliant);
_turnoutData.closed = close;
return true; return true;
} }
@@ -472,7 +461,6 @@
bool VpinTurnout::setClosedInternal(bool close) { bool VpinTurnout::setClosedInternal(bool close) {
IODevice::write(_vpinTurnoutData.vpin, close); IODevice::write(_vpinTurnoutData.vpin, close);
_turnoutData.closed = close;
return true; return true;
} }
@@ -523,7 +511,10 @@
bool LCNTurnout::setClosedInternal(bool close) { bool LCNTurnout::setClosedInternal(bool close) {
// Assume that the LCN command still uses 1 for throw and 0 for close... // Assume that the LCN command still uses 1 for throw and 0 for close...
LCN::send('T', _turnoutData.id, !close); LCN::send('T', _turnoutData.id, !close);
// The _turnoutData.closed flag should be updated by a message from the LCN master, later. // The _turnoutData.closed flag should be updated by a message from the LCN master.
// but in this implementation it is updated in setClosedStateOnly() instead.
// If the LCN master updates this, setClosedStateOnly() and all setClosedInternal()
// have to be updated accordingly so that the closed flag is only set once.
return true; return true;
} }

View File

@@ -125,17 +125,18 @@ wifiSerialState WifiInterface::setup(Stream & setupStream, const FSH* SSid, con
wifiState = setup2( SSid, password, hostname, port, channel); wifiState = setup2( SSid, password, hostname, port, channel);
if (wifiState == WIFI_NOAT) { if (wifiState == WIFI_NOAT) {
DIAG(F("++ Wifi Setup NO AT ++")); LCD(4, F("WiFi no AT chip"));
return wifiState; return wifiState;
} }
if (wifiState == WIFI_CONNECTED) { if (wifiState == WIFI_CONNECTED) {
StringFormatter::send(wifiStream, F("ATE0\r\n")); // turn off the echo StringFormatter::send(wifiStream, F("ATE0\r\n")); // turn off the echo
checkForOK(200, true); checkForOK(200, true);
DIAG(F("WiFi CONNECTED"));
// LCD already shows IP
} else {
LCD(4,F("WiFi DISCON."));
} }
DIAG(F("++ Wifi Setup %S ++"), wifiState == WIFI_CONNECTED ? F("CONNECTED") : F("DISCONNECTED"));
return wifiState; return wifiState;
} }

View File

@@ -125,10 +125,10 @@ The configuration file for DCC-EX Command Station
// define LCD_DRIVER for I2C address 0x27, 16 cols, 2 rows // define LCD_DRIVER for I2C address 0x27, 16 cols, 2 rows
// #define LCD_DRIVER 0x27,16,2 // #define LCD_DRIVER 0x27,16,2
//OR define OLED_DRIVER width,height in pixels (address auto detected) //OR define OLED_DRIVER width,height[,address] in pixels (address auto detected if not supplied)
// 128x32 or 128x64 I2C SSD1306-based devices are supported. // 128x32 or 128x64 I2C SSD1306-based devices are supported.
// Use 132,64 for a SH1106-based I2C device with a 128x64 display. // Use 132,64 for a SH1106-based I2C device with a 128x64 display.
// #define OLED_DRIVER 128,32 // #define OLED_DRIVER 128,32,0x3c
// Define scroll mode as 0, 1 or 2 // Define scroll mode as 0, 1 or 2
// * #define SCROLLMODE 0 is scroll continuous (fill screen if poss), // * #define SCROLLMODE 0 is scroll continuous (fill screen if poss),
@@ -225,7 +225,4 @@ The configuration file for DCC-EX Command Station
//#define SERIAL_BT_COMMANDS //#define SERIAL_BT_COMMANDS
// FastClock Enabler
// To build the FastClock code into the CS please uncomment the line below
//#define USEFASTCLOCK
///////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////

169
config.h.txt Normal file
View File

@@ -0,0 +1,169 @@
/**********************************************************************
Config.h
COPYRIGHT (c) 2013-2016 Gregg E. Berman
COPYRIGHT (c) 2020 Fred Decker
The configuration file for DCC++ EX Command Station
**********************************************************************/
/////////////////////////////////////////////////////////////////////////////////////
// NOTE: Before connecting these boards and selecting one in this software
// check the quick install guides!!! Some of these boards require a voltage
// generating resitor on the current sense pin of the device. Failure to select
// the correct resistor could damage the sense pin on your Arduino or destroy
// the device.
//
// DEFINE MOTOR_SHIELD_TYPE BELOW ACCORDING TO THE FOLLOWING TABLE:
//
// STANDARD_MOTOR_SHIELD : Arduino Motor shield Rev3 based on the L298 with 18V 2A per channel
// POLOLU_MOTOR_SHIELD : Pololu MC33926 Motor Driver (not recommended for prog track)
// FUNDUMOTO_SHIELD : Fundumoto Shield, no current sensing (not recommended, no short protection)
// FIREBOX_MK1 : The Firebox MK1
// FIREBOX_MK1S : The Firebox MK1S
// |
// +-----------------------v
//
// #define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"),
// new MotorDriver(3, 12, UNUSED_PIN, 9, A0, 0.488, 1500, UNUSED_PIN),
// new MotorDriver(11, 13, UNUSED_PIN, 8, A1, 0.488, 1500, UNUSED_PIN)
#define MOTOR_SHIELD_TYPE STANDARD_MOTOR_SHIELD
/////////////////////////////////////////////////////////////////////////////////////
//
// The IP port to talk to a WIFI or Ethernet shield.
//
#define IP_PORT 2560
/////////////////////////////////////////////////////////////////////////////////////
//
// NOTE: Only supported on Arduino Mega
// Set to false if you not even want it on the Arduino Mega
//
//#define ENABLE_WIFI true
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE WiFi Parameters (only in effect if WIFI is on)
//
// If DONT_TOUCH_WIFI_CONF is set, all WIFI config will be done with
// the <+> commands and this sketch will not change anything over
// AT commands and the other WIFI_* defines below do not have any effect.
//#define DONT_TOUCH_WIFI_CONF
//
// WIFI_SSID is the network name IF you want to use your existing home network.
// Do NOT change this if you want to use the WiFi in Access Point (AP) mode.
//
// If you do NOT set the WIFI_SSID, the WiFi chip will first try
// to connect to the previously configured network and if that fails
// fall back to Access Point mode. The SSID of the AP will be
// automatically set to DCCEX_*.
//
// Your SSID may not conain ``"'' (double quote, ASCII 0x22).
#define WIFI_SSID "Your network name"
//
// WIFI_PASSWORD is the network password for your home network or if
// you want to change the password from default AP mode password
// to the AP password you want.
// Your password may not conain ``"'' (double quote, ASCII 0x22).
#define WIFI_PASSWORD "deadcafe"
//
// WIFI_HOSTNAME: You probably don't need to change this
#define WIFI_HOSTNAME "dccex"
//
/////////////////////////////////////////////////////////////////////////////////////
//
// Wifi connect timeout in milliseconds. Default is 14000 (14 seconds). You only need
// to set this if you have an extremely slow Wifi router.
//
#define WIFI_CONNECT_TIMEOUT 14000
/////////////////////////////////////////////////////////////////////////////////////
//
// ENABLE_ETHERNET: Set to true if you have an Arduino Ethernet card (wired). This
// is not for Wifi. You will then need the Arduino Ethernet library as well
//
//#define ENABLE_ETHERNET true
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE STATIC IP ADDRESS *OR* COMMENT OUT TO USE DHCP
//
//#define IP_ADDRESS { 192, 168, 1, 31 }
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE MAC ADDRESS ARRAY FOR ETHERNET COMMUNICATIONS INTERFACE
//
// Uncomment to use with Ethernet Shields
//
// Ethernet Shields do not have have a MAC address in hardware. There may be one on
// a sticker on the Shield that you should use. Otherwise choose one of the ones below
// Be certain that no other device on your network has this same MAC address!
//
// 52:b8:8a:8e:ce:21
// e3:e9:73:e1:db:0d
// 54:2b:13:52:ac:0c
// NOTE: This is not used with ESP8266 WiFi modules.
//#define MAC_ADDRESS { 0x52, 0xB8, 0x8A, 0x8E, 0xCE, 0x21 } // MAC address of your networking card found on the sticker on your card or take one from above
//
// #define MAC_ADDRESS { 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xEF }
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE LCD SCREEN USAGE BY THE BASE STATION
//
// Note: This feature requires an I2C enabled LCD screen using a Hitachi HD44780
// controller and a PCF8574 based I2C 'backpack',
// OR an I2C Oled screen based on SSD1306 (128x64 or 128x32) controller,
// OR an I2C Oled screen based on SH1106 (132x64) controller.
// To enable, uncomment one of the lines below
// define LCD_DRIVER for I2C LCD address 0x3f,16 cols, 2 rows
//#define LCD_DRIVER {SubBus_4,0x27},20,4
//OR define OLED_DRIVER width,height in pixels (address auto detected)
#if defined(ARDUINO_ARCH_STM32)
#define OLED_DRIVER 0x3c, 128, 64
#else
#define OLED_DRIVER {SubBus_0,0x3c}, 128, 32
#endif
#define SCROLLMODE 1
/////////////////////////////////////////////////////////////////////////////////////
// DISABLE EEPROM
//
// If you do not need the EEPROM at all, you can disable all the code that saves
// data in the EEPROM. You might want to do that if you are in a Arduino UNO
// and want to use the EX-RAIL automation. Otherwise you do not have enough RAM
// to do that. Of course, then none of the EEPROM related commands work.
//
#define DISABLE_EEPROM
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE TURNOUTS/ACCESSORIES FOLLOW NORM RCN-213
//
// According to norm RCN-213 a DCC packet with a 1 is closed/straight
// and one with a 0 is thrown/diverging. In DCC++ Classic, and in previous
// versions of DCC++EX, a turnout throw command was implemented in the packet as
// '1' and a close command as '0'. The #define below makes the states
// match with the norm. But we don't want to cause havoc on existent layouts,
// so we define this only for new installations. If you don't want this,
// don't add it to your config.h.
//#define DCC_TURNOUTS_RCN_213
// The following #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
// (throw turnout).
//#define DCC_ACCESSORY_RCN_213
/////////////////////////////////////////////////////////////////////////////////////

View File

@@ -69,10 +69,10 @@ else
# need to do this config better # need to do this config better
cp -p config.example.h config.h cp -p config.example.h config.h
fi fi
need curl
if test -x "$ACLI" ; then if test -x "$ACLI" ; then
: all well : all well
else else
need curl
curl "$ACLIINSTALL" > acliinstall.sh curl "$ACLIINSTALL" > acliinstall.sh
chmod +x acliinstall.sh chmod +x acliinstall.sh
./acliinstall.sh ./acliinstall.sh

View File

@@ -23,7 +23,9 @@
* *
*/ */
// This is the startup sequence, AKA SEQUENCE(0) // This is the startup sequence,
AUTOSTART
POWERON // turn on track power
SENDLOCO(3,1) // send loco 3 off along route 1 SENDLOCO(3,1) // send loco 3 off along route 1
SENDLOCO(10,2) // send loco 10 off along route 2 SENDLOCO(10,2) // send loco 10 off along route 2
DONE // This just ends the startup thread, leaving 2 others running. DONE // This just ends the startup thread, leaving 2 others running.

465
myHal.cpp.txt Normal file
View File

@@ -0,0 +1,465 @@
#include "defines.h"
#include "IODevice.h"
#ifndef IO_NO_HAL
#include "IO_VL53L0X.h"
#include "IO_HCSR04.h"
#include "Sensors.h"
#include "Turnouts.h"
#include "IO_DFPlayer.h"
//#include "IO_Wire.h"
#include "IO_AnalogueInputs.h"
#if __has_include("IO_Servo.h")
#include "IO_Servo.h"
#include "IO_PCA9685pwm.h"
#endif
#include "IO_HALDisplay.h"
#include "LiquidCrystal_I2C.h"
#if __has_include("IO_CMRI.h")
#include "IO_CMRI.h"
#endif
//#include "IO_ExampleSerial.h"
//#include "IO_EXFastclock.h"
//#include "IO_EXTurntable.h"
#if __has_include("IO_ExternalEEPROM.h")
#include "IO_ExternalEEPROM.h"
#endif
#if __has_include("IO_Network.h")
#include "IO_Network.h"
#include "Net_RF24.h"
#include "Net_ENC28J60.h"
#include "Net_Ethernet.h"
#define NETWORK_PRESENT
#endif
#include "IO_TouchKeypad.h"
#define WIRE_TEST 0
#define TESTHARNESS 1
#define I2C_STRESS_TEST 0
#define I2C_SETCLOCK 0
#include "DCC.h"
#if 0 // Long Strings
#define s10 "0123456789"
#define s100 s10 s10 s10 s10 s10 s10 s10 s10 s10 s10
#define s1k s100 s100 s100 s100 s100 s100 s100 s100 s100 s100
#define s10k s1k s1k s1k s1k s1k s1k s1k s1k s1k s1k
#define s32k s10k s10k s10k s1k s1k
volatile const char PROGMEM ss1[] = s32k;
#endif
#if TESTHARNESS
// Function to be invoked by test harness
void myTest() {
// DIAG(F("VL53L0X #1 Test: dist=%d signal=%d ambient=%d value=%d"),
// IODevice::readAnalogue(5000),
// IODevice::readAnalogue(5001),
// IODevice::readAnalogue(5002),
// IODevice::read(5000));
// DIAG(F("VL53L0X #2 Test: dist=%d signal=%d ambient=%d value=%d"),
// IODevice::readAnalogue(5003),
// IODevice::readAnalogue(5004),
// IODevice::readAnalogue(5005),
// IODevice::read(5003));
// DIAG(F("HCSR04 Test: dist=%d value=%d"),
// IODevice::readAnalogue(2000),
// IODevice::read(2000));
// DIAG(F("ADS111x Test: %d %d %d %d %d"),
// IODevice::readAnalogue(4500),
// IODevice::readAnalogue(4501),
// IODevice::readAnalogue(4502),
// IODevice::readAnalogue(4503),
// IODevice::readAnalogue(A5)
// );
// DIAG(F("RF24 Test: 4000:%d 4002:%d"),
// IODevice::read(4000),
// IODevice::read(4002)
// );
DIAG(F("EXPANDER: 2212:%d 2213:%d 2214:%d"),
IODevice::readAnalogue(2212),
IODevice::readAnalogue(2213),
IODevice::readAnalogue(2214));
}
#endif
#if I2C_STRESS_TEST
static bool initialised = false;
static uint8_t lastStatus = 0;
static const int nRBs = 3; // request blocks concurrently
static const int I2cTestPeriod = 1; // milliseconds
static I2CAddress testDevice = {SubBus_6, 0x27};
static I2CRB rb[nRBs];
static uint8_t readBuffer[nRBs*32]; // nRB x 32-byte input buffer
static uint8_t writeBuffer[nRBs]; // nRB x 1-byte output buffer
static unsigned long count = 0;
static unsigned long errors = 0;
static unsigned long lastOutput = millis();
void I2CTest() {
if (!initialised) {
// I2C Loading for stress test.
// Write value then read back 32 times
for (int i=0; i<nRBs; i++) {
writeBuffer[i] = (0xc5 ^ i ^ i<<3 ^ i<<6) & ~0x08; // bit corresponding to 08 is hard-wired low
rb[i].setRequestParams(testDevice, &readBuffer[i*32], 32,
&writeBuffer[i], 1);
I2CManager.queueRequest(&rb[i]);
}
initialised = true;
}
for (int i=0; i<nRBs; i++) {
if (!rb[i].isBusy()) {
count++;
uint8_t status = rb[i].status;
if (status != lastStatus) {
DIAG(F("I2CTest: status=%d (%S)"),
(int)status, I2CManager.getErrorMessage(status));
lastStatus = status;
}
if (status == I2C_STATUS_OK) {
bool diff = false;
// Check contents of response
for (uint8_t j=0; j<32; j++) {
if (readBuffer[i*32+j] != writeBuffer[i]) {
DIAG(F("I2CTest: Received message mismatch, sent %2x rcvd %2x"),
writeBuffer[i], readBuffer[i*32+j]);
diff = true;
}
}
if (diff) errors++;
} else
errors++;
I2CManager.queueRequest(&rb[i]);
}
}
if (millis() - lastOutput > 60000) { // 1 minute
DIAG(F("I2CTest: Count=%l Errors=%l"), count, errors);
count = errors = 0;
lastOutput = millis();
}
}
#endif
void updateLocoScreen() {
for (int i=0; i<8; i++) {
if (DCC::speedTable[i].loco > 0) {
int speed = DCC::speedTable[i].speedCode;
char direction = (speed & 0x80) ? 'R' : 'F';
speed = speed & 0x7f;
if (speed > 0) speed = speed - 1;
SCREEN(3, i, F("Loco:%4d %3d %c"), DCC::speedTable[i].loco,
speed, direction);
}
}
}
void updateTime() {
uint8_t buffer[20];
I2CAddress rtc = {SubBus_1, 0x68}; // Real-time clock I2C address
buffer[0] = 0;
// Set time - only needs to be done once if battery is ok.
static bool timeSet = false;
if (!timeSet) {
// I2CManager.read(rtc, buffer+1, sizeof(buffer)-1);
// uint8_t year = 23; // 2023
// uint8_t day = 2; // tuesday
// uint8_t date = 21; // 21st
// uint8_t month = 2; // feb
// uint8_t hours = 23; // xx:
// uint8_t minutes = 25; // :xx
// buffer[1] = 0; // seconds
// buffer[2] = ((minutes / 10) << 4) | (minutes % 10);
// buffer[3] = ((hours / 10) << 4) | (hours % 10);
// buffer[4] = day;
// buffer[5] = ((date/10) << 4) + date%10; // 24th
// buffer[6] = ((month/10) << 4) + month%10; // feb
// buffer[7] = ((year/10) << 4) + year%10; // xx23
// for (uint8_t i=8; i<sizeof(buffer); i++) buffer[i] = 0;
// I2CManager.write(rtc, buffer, sizeof(buffer));
timeSet = true;
}
uint8_t status = I2CManager.read(rtc, buffer+1, sizeof(buffer)-1, 1, 0);
if (status == I2C_STATUS_OK) {
uint8_t seconds10 = buffer[1] >> 4;
uint8_t seconds1 = buffer[1] & 0xf;
uint8_t minutes10 = buffer[2] >> 4;
uint8_t minutes1 = buffer[2] & 0xf;
uint8_t hours10 = buffer[3] >> 4;
uint8_t hours1 = buffer[3] & 0xf;
SCREEN(10, 0, F("Departures %d%d:%d%d:%d%d"),
hours10, hours1, minutes10, minutes1, seconds10, seconds1);
}
}
void showCharacterSet() {
if (millis() < 3000) return;
const uint8_t lineLen = 20;
char buffer[lineLen+1];
static uint8_t nextChar = 0x20;
for (uint8_t row=0; row<8; row+=1) {
for (uint8_t col=0; col<lineLen; col++) {
buffer[col] = nextChar++;
buffer[++col] = ' ';
if (nextChar == 0) nextChar = 0x20; // check for wrap-around
}
buffer[lineLen] = '\0';
SCREEN(3, row, F("%s"), buffer);
}
}
#if defined(ARDUINO_NUCLEO_F446RE)
HardwareSerial Serial3(PC11, PC10);
#endif
// HAL device initialisation
void halSetup() {
I2CManager.setTimeout(500); // microseconds
I2CManager.forceClock(400000);
HALDisplay<OLED>::create(10, {SubBus_5, 0x3c}, 132, 64); // SH1106
// UserAddin::create(updateLocoScreen, 1000);
// UserAddin::create(showCharacterSet, 5000);
// UserAddin::create(updateTime, 1000);
HALDisplay<OLED>::create(10, {SubBus_4, 0x3c}, 128, 32);
HALDisplay<OLED>::create(10, {SubBus_7, 0x3c}, 128, 32);
//HALDisplay<LiquidCrystal_I2C>::create(10, {SubBus_4, 0x27}, 20, 4);
// Draw double boxes with X O O X inside.
// SCREEN(3, 2, F("\xc9\xcd\xcd\xcd\xcb\xcd\xcd\xcd\xcb\xcd\xcd\xcd\xcb\xcd\xcd\xcd\xcb\xcd\xcd\xcd\xbb"));
// SCREEN(3, 3, F("\xba X \xba O \xba O \xba O \xba X \xba"));
// SCREEN(3, 4, F("\xcc\xcd\xcd\xcd\xce\xcd\xcd\xcd\xce\xcd\xcd\xcd\xce\xcd\xcd\xcd\xce\xcd\xcd\xcd\xb9"));
// SCREEN(3, 5, F("\xba X \xba O \xba O \xba O \xba X \xba"));
// SCREEN(3, 6, F("\xc8\xcd\xcd\xcd\xca\xcd\xcd\xcd\xca\xcd\xcd\xcd\xca\xcd\xcd\xcd\xca\xcd\xcd\xcd\xbc"));
// Draw single boxes with X O O X inside.
// SCREEN(3, 0, F("Summary Data:"));
// SCREEN(3, 1, F("\xda\xc4\xc4\xc4\xc2\xc4\xc4\xc4\xc2\xc4\xc4\xc4\xc2\xc4\xc4\xc4\xc2\xc4\xc4\xc4\xbf"));
// SCREEN(3, 2, F("\xb3 X \xb3 O \xb3 O \xb3 O \xb3 X \xb3"));
// SCREEN(3, 3, F("\xc3\xc4\xc4\xc4\xc5\xc4\xc4\xc4\xc5\xc4\xc4\xc4\xc5\xc4\xc4\xc4\xc5\xc4\xc4\xc4\xb4"));
// SCREEN(3, 4, F("\xb3 X \xb3 O \xb3 O \xb3 O \xb3 X \xb3"));
// SCREEN(3, 5, F("\xc3\xc4\xc4\xc4\xc5\xc4\xc4\xc4\xc5\xc4\xc4\xc4\xc5\xc4\xc4\xc4\xc5\xc4\xc4\xc4\xb4"));
// SCREEN(3, 6, F("\xb3 X \xb3 O \xb3 O \xb3 O \xb3 X \xb3"));
// SCREEN(3, 7, F("\xc0\xc4\xc4\xc4\xc1\xc4\xc4\xc4\xc1\xc4\xc4\xc4\xc1\xc4\xc4\xc4\xc1\xc4\xc4\xc4\xd9"));
// Blocks of different greyness
// SCREEN(3, 0, F("\xb0\xb0\xb0\xb0\xb1\xb1\xb1\xb1\xb2\xb2\xb2\xb2\xdb\xdb\xdb\xdb"));
// SCREEN(3, 1, F("\xb0\xb0\xb0\xb0\xb1\xb1\xb1\xb1\xb2\xb2\xb2\xb2\xdb\xdb\xdb\xdb"));
// SCREEN(3, 2, F("\xb0\xb0\xb0\xb0\xb1\xb1\xb1\xb1\xb2\xb2\xb2\xb2\xdb\xdb\xdb\xdb"));
// DCCEX logo
// SCREEN(3, 1, F("\xb0\xb0\x20\x20\x20\xb0\x20\x20\x20\xb0\x20\x20\x20\x20\xb0\xb0\xb0\x20\xb0\x20\xb0"));
// SCREEN(3, 2, F("\xb0\x20\xb0\x20\xb0\x20\xb0\x20\xb0\x20\xb0\x20\x20\x20\xb0\x20\x20\x20\xb0\x20\xb0"));
// SCREEN(3, 3, F("\xb0\x20\xb0\x20\xb0\x20\x20\x20\xb0\x20\x20\x20\xb0\x20\xb0\xb0\x20\x20\x20\xb0\x20"));
// SCREEN(3, 4, F("\xb0\x20\xb0\x20\xb0\x20\xb0\x20\xb0\x20\xb0\x20\x20\x20\xb0\x20\x20\x20\xb0\x20\xb0"));
// SCREEN(3, 5, F("\xb0\xb0\x20\x20\x20\xb0\x20\x20\x20\xb0\x20\x20\x20\x20\xb0\xb0\xb0\x20\xb0\x20\xb0"));
// SCREEN(3, 7, F("\xb1\xb1\xb1\xb1\xb1\xb1\xb1\xb1\xb1\xb1\xb1\xb1\xb1\xb1\xb1\xb1\xb1\xb1\xb1\xb1\xb1"));
#if 0
// List versions of devices that respond to the version request
for (uint8_t address = 8; address<0x78; address++) {
uint8_t buffer[3];
uint8_t status = I2CManager.read(0x7c, buffer, sizeof(buffer), 1, address);
if (status == I2C_STATUS_OK) {
uint16_t manufacturer = ((uint16_t)buffer[0] << 4 ) | (buffer[1] >> 4);
uint16_t deviceID = ((uint16_t)(buffer[1] & 0x0f) << 5) | (buffer[2] >> 3);
uint16_t dieRevision = buffer[2] & 0x1f;
DIAG(F("Addr %s version: %x %x %x"), address.toString(), manufacturer, deviceID, dieRevision);
}
}
#endif
#if I2C_STRESS_TEST
UserAddin::create(I2CTest, I2cTestPeriod);
#endif
#if WIRE_TEST
// Test of Wire-I2CManager interface
Wire.begin();
Wire.setClock(400000);
Wire.beginTransmission(0x23);
Wire.print("Hello");
uint8_t status = Wire.endTransmission();
if (status==0) DIAG(F("Wire: device Found on 0x23"));
Wire.beginTransmission(0x23);
Wire.write(0xde);
Wire.endTransmission(false); // don't send stop
Wire.requestFrom(0x23, 1);
if (Wire.available()) {
DIAG(F("Wire: value=x%x"), Wire.read());
}
uint8_t st = I2CManager.write(0x33, 0, 0);
DIAG(F("I2CManager 0x33 st=%d \"%S\""), st,
I2CManager.getErrorMessage(st));
#endif
#if I2C_SETCLOCK
// Test I2C clock changes
// Set up two I2C request blocks
I2CRB rb1, rb2;
uint8_t readBuff[32];
rb1.setRequestParams(0x23, readBuff, sizeof(readBuff), readBuff, sizeof(readBuff));
rb2.setRequestParams(0x23, readBuff, sizeof(readBuff), readBuff, sizeof(readBuff));
// First set clock to 400kHz and then issue requests
I2CManager.forceClock(400000);
I2CManager.queueRequest(&rb1);
I2CManager.queueRequest(&rb2);
// Wait a little to allow the first transaction to start
delayMicroseconds(2);
// ... then request a clock speed change
I2CManager.forceClock(100000);
DIAG(F("I2CClock: rb1 status=%d"), rb1.wait());
DIAG(F("I2CClock: rb2 status=%d"), rb2.wait());
// Reset clock speed
I2CManager.forceClock(400000);
#endif
EXIOExpander::create(2200, 18, {SubBus_0, 0x65});
//UserAddin::create(myTest, 1000);
// ServoTurnout::create(2200, 2200, 400, 200, 0);
// ServoTurnout::create(2200, 2200, 400, 200, 0);
TouchKeypad::create(2300, 16, 25, 24);
// GPIO
PCF8574::create(800, 8, {SubBus_1, 0x23});
//PCF8574::create(808, 8, {SubBus_2, 0x27});
PCF8574::create(65000, 8, 0x27);
MCP23017::create(164,16,{SubBus_3, 0x20});
//MCP23017::create(180,16,{SubBus_0, 0x27});
Sensor::create(170, 170, 1); // Hall effect, enable pullup.
Sensor::create(171, 171, 1);
// PWM (LEDs and Servos)
// For servos, use default 50Hz pulses.
PCA9685::create(100, 16, {SubBus_1, 0x41});
// For LEDs, use 1kHz pulses.
PCA9685::create(116, 16, {SubBus_1, 0x40}, 1000);
// 4-pin Analogue Input Module
//ADS111x::create(4500, 4, 0x48);
// Laser Time-Of-Flight Sensors
VL53L0X::create(5000, 3, {SubBus_0, 0x60}, 300, 310, 46);
//VL53L0X::create(5003, 3, {SubBus_6, 0x61}, 300, 310, 47);
Sensor::create(5000, 5000, 0);
Sensor::create(5003, 5003, 0);
// Monitor reset digital on first TOF
//Sensor::create(46,46,0);
// // External 24C256 EEPROM (256kBytes) on I2C address 0x50.
// ExternalEEPROM::create({SubBus_0, 0x50}, 256);
// Play up to 10 sounds on pins 10000-10009. Player is connected to Serial1 or Serial2.
#if defined(HAVE_HWSERIAL1) && !defined(ARDUINO_ARCH_STM32)
DFPlayer::create(10000, 14, Serial1);
#elif defined(ARDUINO_ARCH_STM32)
DFPlayer::create(10000, 10, Serial3); // Pins PC11 (RX) and PC10 (TX)
#endif
// Ultrasound echo device
HCSR04::create(2000, 32, 33, 80, 85 /*, HCSR04::LOOP */);
Sensor::create(2000, 2000, 0);
#if __has_include("IO_CMRI.h")
CMRIbus::create(0, Serial2, 115200, 50, 40); // 50ms cycle, pin 40 for DE/!RE pins
CMRInode::create(25000, 72, 0, 0, 'M'); // SMINI address 0
for (int pin=0; pin<24; pin++) {
Sensor::create(25000+pin, 25000+pin, 0);
}
#endif
//CMRInode::create(25072, 72, 0, 13, 'M'); // SMINI address 13
//CMRInode::create(25144, 288, 0, 14, 'C', 144, 144); // CPNODE address 14
#ifdef NETWORK_PRESENT
// Define remote pins to be used. The range of remote pins is like a common data area shared
// between all nodes.
// For outputs, a write to a remote VPIN causes a message to be sent to another node, which then performs
// the write operation on the device VPIN that is local to that node.
// For inputs, the state of remote input VPIN is read on the node where it is connected, and then
// sent to other nodes in the system where the state is saved and processed. Updates are sent on change, and
// also periodically if no changes.
//
// Each definition is a triple of remote node, remote pin, indexed by relative pin. Up to 224 rpins can
// be configured (per node). This is to fit into a 32-byte packet.
REMOTEPINS rpins[] = {
{30,164,RPIN_IN} , //4000 Node 30, first MCP23017 pin, input
{30,165,RPIN_IN}, //4001 Node 30, second MCP23017 pin, input
{30,166,RPIN_OUT}, //4002 Node 30, third MCP23017 pin, output
{30,166,RPIN_OUT}, //4003 Node 30, fourth MCP23017 pin, output
{30,100,RPIN_INOUT}, //4004 Node 30, first PCA9685 servo pin
{30,101,RPIN_INOUT}, //4005 Node 30, second PCA9685 servo pin
{30,102,RPIN_INOUT}, //4006 Node 30, third PCA9685 servo pin
{30,103,RPIN_INOUT}, //4007 Node 30, fourth PCA9685 servo pin
{30,24,RPIN_IN}, //4008 Node 30, Arduino pin D24
{30,25,RPIN_IN}, //4009 Node 30, Arduino pin D25
{30,26,RPIN_IN}, //4010 Node 30, Arduino pin D26
{30,27,RPIN_IN}, //4011 Node 30, Arduino pin D27
{30,1000,RPIN_OUT}, //4012 Node 30, DFPlayer playing flag (when read) / Song selector (when written)
{30,5000,RPIN_IN}, //4013 Node 30, VL53L0X detect pin
{30,VPIN_NONE,0}, //4014 Node 30, spare
{30,VPIN_NONE,0}, //4015 Node 30, spare
{31,164,RPIN_IN} , //4016 Node 31, first MCP23017 pin, input
{31,165,RPIN_IN}, //4017 Node 31, second MCP23017 pin, input
{31,166,RPIN_OUT}, //4018 Node 31, third MCP23017 pin, output
{31,166,RPIN_OUT}, //4019 Node 31, fourth MCP23017 pin, output
{31,100,RPIN_INOUT}, //4020 Node 31, first PCA9685 servo pin
{31,101,RPIN_INOUT}, //4021 Node 31, second PCA9685 servo pin
{31,102,RPIN_INOUT}, //4022 Node 31, third PCA9685 servo pin
{31,103,RPIN_INOUT}, //4023 Node 31, fourth PCA9685 servo pin
{31,24,RPIN_IN}, //4024 Node 31, Arduino pin D24
{31,25,RPIN_IN}, //4025 Node 31, Arduino pin D25
{31,26,RPIN_IN}, //4026 Node 31, Arduino pin D26
{31,27,RPIN_IN}, //4027 Node 31, Arduino pin D27
{31,3,RPIN_IN}, //4028 Node 31, Arduino pin D3
{31,VPIN_NONE,0}, //4029 Node 31, spare
{31,VPIN_NONE,0}, //4030 Node 31, spare
{31,VPIN_NONE,0} //4031 Node 31, spare
};
// FirstVPIN, nPins, thisNode, pinDefs, CEPin, CSNPin
// Net_RF24 *rf24Driver = new Net_RF24(48, 49);
// Network<Net_RF24>::create(4000, NUMREMOTEPINS(rpins), NODE, rpins, rf24Driver);
#if NODE==30
//Net_ENC28J60 *encDriver = new Net_ENC28J60(49);
//Network<Net_ENC28J60>::create(4000, NUMREMOTEPINS(rpins), NODE, rpins, encDriver);
#elif NODE==31
Net_ENC28J60 *encDriver = new Net_ENC28J60(53);
Network<Net_ENC28J60>::create(4000, NUMREMOTEPINS(rpins), NODE, rpins, encDriver);
#else
Net_Ethernet *etherDriver = new Net_Ethernet();
Network<Net_Ethernet>::create(4000, NUMREMOTEPINS(rpins), NODE, rpins, etherDriver);
#endif
for (int i=0; i<=32; i++)
Sensor::create(4000+i, 4000+i, 0);
#endif
#ifdef ARDUINO_ARCH_STM32
//PCF8574::create(1900, 8, 0x27);
Sensor::create(1900,100,1);
Sensor::create(1901,101,1);
#endif
}
#endif // IO_NO_HAL

View File

@@ -17,9 +17,11 @@
// Include devices you need. // Include devices you need.
#include "IODevice.h" #include "IODevice.h"
#include "IO_HCSR04.h" // Ultrasonic range sensor //#include "IO_HALDisplay.h" // Auxiliary display devices (LCD/OLED)
#include "IO_VL53L0X.h" // Laser time-of-flight sensor //#include "IO_HCSR04.h" // Ultrasonic range sensor
#include "IO_DFPlayer.h" // MP3 sound player //#include "IO_VL53L0X.h" // Laser time-of-flight sensor
//#include "IO_DFPlayer.h" // MP3 sound player
//#include "IO_TouchKeypad.h // Touch keypad with 16 keys
//#include "IO_EXTurntable.h" // Turntable-EX turntable controller //#include "IO_EXTurntable.h" // Turntable-EX turntable controller
//#include "IO_EXFastClock.h" // FastClock driver //#include "IO_EXFastClock.h" // FastClock driver
@@ -31,6 +33,61 @@
void halSetup() { void halSetup() {
//=======================================================================
// The following directives define auxiliary display devices.
// These can be defined in addition to the system display (display
// number 0) that is defined in config.h.
// A write to a line which is beyond the length of the screen will overwrite
// the bottom line, unless the line number is 255 in which case the
// screen contents will scroll up before the text is written to the
// bottom line.
//=======================================================================
//
// Create a 128x32 OLED display device as display number 1
// (line 0 is written by EX-RAIL 'SCREEN(1, 0, "text")').
//HALDisplay<OLED>::create(1, 0x3d, 128, 32);
// Create a 20x4 LCD display device as display number 2
// (line 0 is written by EX-RAIL 'SCREEN(2, 0, "text")').
// HALDisplay<LiquidCrystal>(2, 0x27, 20, 4);
//=======================================================================
// User Add-ins
//=======================================================================
// User add-ins can be created when you want to do something that
// can't be done in EX-RAIL but does not merit a HAL driver. The
// user add-in is a C++ function that is executed periodically by the
// HAL subsystem.
// Example: The function will be executed once per second and will display,
// on screen #3, the first eight entries (assuming an 8-line display)
// from the loco speed table.
// Put the following block of code in myHal.cpp OUTSIDE of the
// halSetup() function:
//
// void updateLocoScreen() {
// for (int i=0; i<8; i++) {
// if (DCC::speedTable[i].loco > 0) {
// int speed = DCC::speedTable[i].speedCode;
// char direction = (speed & 0x80) ? 'R' : 'F';
// speed = speed & 0x7f;
// if (speed > 0) speed = speed - 1;
// SCREEN(3, i, F("Loco:%4d %3d %c"), DCC::speedTable[i].loco,
// speed, direction);
// }
// }
// }
//
// Put the following line INSIDE the halSetup() function:
//
// UserAddin::create(updateLocoScreen, 1000);
//
//======================================================================= //=======================================================================
// The following directive defines a PCA9685 PWM Servo driver module. // The following directive defines a PCA9685 PWM Servo driver module.
//======================================================================= //=======================================================================
@@ -176,6 +233,21 @@ void halSetup() {
// DFPlayer::create(10000, 10, Serial1); // DFPlayer::create(10000, 10, Serial1);
//=======================================================================
// 16-pad capacitative touch key pad based on TP229 IC.
//=======================================================================
// Parameters below:
// 11000 = first VPIN allocated
// 16 = number of VPINs allocated
// 25 = local GPIO pin number for clock signal
// 24 = local GPIO pin number for data signal
//
// Pressing the key pads numbered 1-16 cause each of the nominated digital VPINs
// (11000-11015 in this case) to be activated.
// TouchKeypad::create(11000, 16, 25, 24);
//======================================================================= //=======================================================================
// The following directive defines an EX-Turntable turntable instance. // The following directive defines an EX-Turntable turntable instance.
//======================================================================= //=======================================================================

View File

@@ -20,11 +20,11 @@ default_envs =
ESP32 ESP32
Nucleo-F411RE Nucleo-F411RE
Nucleo-F446RE Nucleo-F446RE
Teensy3.2 Teensy3_2
Teensy3.5 Teensy3_5
Teensy3.6 Teensy3_6
Teensy4.0 Teensy4_0
Teensy4.1 Teensy4_1
src_dir = . src_dir = .
include_dir = . include_dir = .
@@ -53,7 +53,7 @@ monitor_speed = 115200
monitor_echo = yes monitor_echo = yes
build_flags = -std=c++17 build_flags = -std=c++17
[env:Arduino M0] [env:Arduino-M0]
platform = atmelsam platform = atmelsam
board = mzeroUSB board = mzeroUSB
framework = arduino framework = arduino
@@ -192,7 +192,7 @@ build_flags = -std=c++17 -Os -g2 -Wunused-variable -DDIAG_LOOPTIMES ; -DDIAG_IO
monitor_speed = 115200 monitor_speed = 115200
monitor_echo = yes monitor_echo = yes
[env:Teensy3.2] [env:Teensy3_2]
platform = teensy platform = teensy
board = teensy31 board = teensy31
framework = arduino framework = arduino
@@ -200,7 +200,7 @@ build_flags = -std=c++17 -Os -g2
lib_deps = ${env.lib_deps} lib_deps = ${env.lib_deps}
lib_ignore = NativeEthernet lib_ignore = NativeEthernet
[env:Teensy3.5] [env:Teensy3_5]
platform = teensy platform = teensy
board = teensy35 board = teensy35
framework = arduino framework = arduino
@@ -208,7 +208,7 @@ build_flags = -std=c++17 -Os -g2
lib_deps = ${env.lib_deps} lib_deps = ${env.lib_deps}
lib_ignore = NativeEthernet lib_ignore = NativeEthernet
[env:Teensy3.6] [env:Teensy3_6]
platform = teensy platform = teensy
board = teensy36 board = teensy36
framework = arduino framework = arduino
@@ -216,7 +216,7 @@ build_flags = -std=c++17 -Os -g2
lib_deps = ${env.lib_deps} lib_deps = ${env.lib_deps}
lib_ignore = NativeEthernet lib_ignore = NativeEthernet
[env:Teensy4.0] [env:Teensy4_0]
platform = teensy platform = teensy
board = teensy40 board = teensy40
framework = arduino framework = arduino
@@ -224,7 +224,7 @@ build_flags = -std=c++17 -Os -g2
lib_deps = ${env.lib_deps} lib_deps = ${env.lib_deps}
lib_ignore = NativeEthernet lib_ignore = NativeEthernet
[env:Teensy4.1] [env:Teensy4_1]
platform = teensy platform = teensy
board = teensy41 board = teensy41
framework = arduino framework = arduino

View File

@@ -4,7 +4,39 @@
#include "StringFormatter.h" #include "StringFormatter.h"
#define VERSION "4.2.18" #define VERSION "4.2.41"
// 4.2.41 - Move HAl startup to ASAP in setup()
// - Fix DNOU8 output pin setup to all LOW
// 4.2.40 - Automatically detect conflicting default I2C devices and disable
// 4.2.39 - DFplayer driver now polls device to detect failures and errors.
// 4.2.38 - Clean up compiler warning when IO_RotaryEncoder.h included
// 4.2.37 - Add new FLAGS HAL device for communications to/from EX-RAIL;
// - Fix diag display of high VPINs within IODevice class.
// 4.2.36 - do not broadcast a turnout state that has not changed
// - Use A2/A3 for current sensing on ESP32 + Motor Shield
// 4.2.35 - add <z> direct pin manipulation command
// 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 !!)
// 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
// 4.2.28 - Reinstate use of timer11 in STM32 - remove HA mode.
// - Update IO_DFPlayer to work with MP3-TF-16P rev3.
// 4.2.27 - Bugfix LCD showed random characters in SCROLLMODE 2
// 4.2.26 - EX-IOExpander device driver enhancements
// - Enhance I2C error checking
// - Introduce delays to _loop to allow room for other I2C device comms
// - Improve analogue read reliability
// 4.2.25 - Bugfix SAMD21 Exrail odd byte boundary
// 4.2.24 - Bugfix Ethernet shield: Static IP now possible
// 4.2.23 - Bugfix signalpin2 was not set up in shadow port
// 4.2.22 - Implement broadcast of Track Manager changes
// 4.2.21 - Implement non-blocking I2C for EX-IOExpander device driver
// 4.2.20 - <JG> & <JI> commands for multi-track gauges
// - Reinstate <c> but remember its a bit useless when TM involved.
// 4.2.19 - Bugfix for analog reading of track current sensor offset.
// 4.2.18 - I2C Multiplexer support through Extended Addresses, // 4.2.18 - I2C Multiplexer support through Extended Addresses,
// added for Wire, 4209 and AVR I2C drivers. // added for Wire, 4209 and AVR I2C drivers.
// - I2C retries when an operation fails. // - I2C retries when an operation fails.