1
0
mirror of https://github.com/DCC-EX/CommandStation-EX.git synced 2024-11-24 16:46:13 +01:00

Compare commits

..

98 Commits

Author SHA1 Message Date
Asbelos
a021895758 Merge branch 'devel' into devel_lcc 2023-10-12 19:50:07 +01:00
peteGSX
5726844c83
Merge pull request #360 from DCC-EX:fix-ifttposition
Fixed
2023-10-13 04:46:05 +10:00
peteGSX
0214a55b23 Fixed 2023-10-13 04:37:38 +10:00
Asbelos
1311dc746a Merge branch 'devel' into devel_lcc 2023-10-12 18:02:05 +01:00
Asbelos
090278ff77 EXRAIL SIGNAL feature fix 2023-10-12 17:07:21 +01:00
Asbelos
7db4a9575a Merge branch 'master' into devel 2023-10-12 11:07:39 +01:00
Asbelos
8b8e9e4919 clean result from invalid <JR n> 2023-10-12 11:07:05 +01:00
peteGSX
ce84974967 Missed one i 2023-10-12 13:42:14 +10:00
peteGSX
034c441c34
Merge pull request #359 from DCC-EX:turntable-broadcast-I
Change broadcast
2023-10-12 13:35:55 +10:00
peteGSX
d5978b1578 Change broadcast 2023-10-12 13:28:39 +10:00
Colin Murdoch
ea4f90d5fc Merged in Power changes
Merge in power changes and EXRAIL command & update to version.h
2023-10-11 17:06:56 +01:00
Colin Murdoch
1181fd855d Merge branch 'devel-power-chm' into devel 2023-10-11 16:58:17 +01:00
Colin Murdoch
a092e06a6f Update .gitignore
added UserAddin.txt to gitignore
2023-10-10 12:11:49 +01:00
Colin Murdoch
68fd56e7fc Added returnDCAddr
Added function to return DC address
2023-10-10 11:52:46 +01:00
Asbelos
370dae0ab8 Merge branch 'master' into devel 2023-10-09 18:15:36 +01:00
Asbelos
bef4b2ec35 fix <JR> default roster 2023-10-09 18:09:48 +01:00
Asbelos
787bf09ed1 A few bits 2023-10-09 17:45:33 +01:00
Colin Murdoch
fe618d0b85 Add getModeName()
Add facility to get the name of the track mode
2023-10-06 19:11:11 +01:00
pmantoine
2ff1619ad1 STM32 reinstate 100% duty cycle PWM 2023-10-04 14:54:06 +08:00
pmantoine
7afd4443d6 STM32 revised I2C clock setup 2023-10-02 12:04:47 +08:00
Colin Murdoch
52cfc18754 Remove Diags not needed
Tidy up Diags and responses - use HASH_KEYWORD in place of 'A'
2023-09-28 15:02:30 +01:00
pmantoine
ed0cfee091 STM32 DCCEXanalogWrite for TrackManager PWM 2023-09-28 17:43:22 +08:00
Colin Murdoch
25bbfa4c68 Fix <1 JOIN>
Fixed <1 JOIN> issue in TrackManager
2023-09-27 14:46:48 +01:00
Colin Murdoch
2a46b96083 Updates to power
Updates to powere routines and EXRAIL
2023-09-26 18:02:39 +01:00
Colin Murdoch
17c004aecf Code corrections
code corrections
2023-09-25 14:32:54 +01:00
Colin Murdoch
9e3ae21bb8 Change to EXRAIL Set_Power
Change to EXRAIL SET_Power
2023-09-25 09:59:17 +01:00
Harald Barth
624656ebc9 date tag 2023-09-24 20:56:27 +02:00
Harald Barth
5a7f278b1e correct return when requesting D RAM 2023-09-24 20:55:16 +02:00
Harald Barth
9333beda49 correct return when requesting D RAM 2023-09-24 20:54:17 +02:00
Colin Murdoch
aacb980dc8 Power control plus EXRAIL
Power Control <0 A> etc plus EXRAIL SET_POWER
Not yet fully tested.
2023-09-24 15:40:42 +01:00
kempe63
11b9fd4ef5 Fixed IO_PCA9555.h to work with PCA9548 mux 2023-09-23 20:25:10 +01:00
kempe63
d07718be8c Revert "Update version.h to 5.1.7"
This reverts commit d57b5ba537.
2023-09-23 20:18:59 +01:00
kempe63
d57b5ba537 Update version.h to 5.1.7 2023-09-23 20:09:01 +01:00
kempe63
dab02ec659 Update IO_PCA9555.h
Now compiles and works on PCA9548 Mux. Tested with MCP23017 and PCA9555 on the same Subbus
2023-09-23 16:10:16 +01:00
kempe63
6ad5326f1d PCA9555 compiles and tested on PCA9548 mux
IO_PCA9555.h added changes that had been applied to IO_MCP23017 for support on PCA9548 Mux. Constructor now also private and type casting of variables made the same for IO_PCA9555. Tested with MCP23017 and PCA9555 simultaneous on the same Mux Subbus
2023-09-23 16:06:14 +01:00
kempe63
39e1363ce0 Merge branch 'devel' of https://github.com/DCC-EX/CommandStation-EX into devel 2023-09-23 16:04:26 +01:00
kempe63
c9d4f5e94d Update IO_PCA9555.h 2023-09-23 15:56:09 +01:00
Colin Murdoch
8052090e0f Added Single Track Power On/Off
Added power On/Off <> commands
2023-09-22 17:03:40 +01:00
pmantoine
dfe3e9d42c STM32 ADCee extensions 2023-09-21 16:09:04 +08:00
pmantoine
5d810a620b STM32 variant support extension and tidy 2023-09-21 16:05:35 +08:00
pmantoine
550ad58c4d STM32 ADCee extended to support ADC2 and ADC3 2023-09-21 14:39:25 +08:00
peteGSX
7a305e179c
Merge pull request #353 from DCC-EX:turntable-fix
Updated broadcasts
2023-09-15 06:32:30 +10:00
peteGSX
8437b0e7aa Updated broadcasts 2023-09-15 06:26:29 +10:00
Harald Barth
46289fa78c Check bad AT firmware version 2023-09-14 09:05:23 +02:00
pmantoine
ebbeea5fbb STM32F4xx native I2C driver merge 2023-09-13 16:46:36 +08:00
pmantoine
a8321fff42
Merge pull request #352 from DCC-EX/STM32_I2C_PMA_NEIL
Stm32 i2 c pma neil
2023-09-13 16:43:59 +08:00
peteGSX
a16790f585
Merge pull request #349 from DCC-EX:add-turntable-object
Add-turntable-object
2023-09-11 05:02:20 +10:00
peteGSX
da6a3c442f Remove redundant line 2023-09-10 18:41:14 +10:00
peteGSX
4fcd81a118 Update version 2023-09-10 07:18:54 +10:00
peteGSX
eb450dbd89
Merge branch 'devel' into add-turntable-object 2023-09-10 07:13:16 +10:00
peteGSX
a0562fdf5c Update defines to match changes in devel 2023-09-10 07:06:27 +10:00
peteGSX
7ee2c29a52 Include HAL create with EXTT_TURNTABLE 2023-09-10 05:30:48 +10:00
peteGSX
dba5d35aa2 Add response to create 2023-09-09 09:23:10 +10:00
peteGSX
be10be5a1a Added angles 2023-09-09 07:22:10 +10:00
peteGSX
bd02d1c15b WAITFORTT ready for testing 2023-09-07 07:58:19 +10:00
peteGSX
004d7b6631 JO and JP working 2023-09-07 07:32:54 +10:00
peteGSX
21ce87eb3e Descriptions available 2023-09-07 05:33:26 +10:00
peteGSX
1f5f7754c1 Start on position description 2023-09-06 15:16:46 +10:00
peteGSX
6adff43f4b Update add position 2023-09-06 07:59:43 +10:00
peteGSX
152f9850bb Working 2023-09-05 19:05:18 +10:00
peteGSX
3094c52bf8 Ready to test 2023-09-05 08:38:37 +10:00
peteGSX
86f4567556 Revisiting logic 2023-09-04 18:46:28 +10:00
peteGSX
dd890e65bf Add move check 2023-09-04 07:38:26 +10:00
peteGSX
1e48c59cd8 Capture progress 2023-09-03 18:54:56 +10:00
peteGSX
004d10ee58 Fix build errors 2023-09-02 18:45:59 +10:00
peteGSX
e734661d1b EXRAIL ready for testing 2023-09-02 08:29:49 +10:00
peteGSX
bcb250bacf Broadcasts working 2023-09-01 18:30:02 +10:00
peteGSX
798241927f Really fix build errors 2023-09-01 13:28:24 +10:00
peteGSX
df2f09f4d2 Fix build errors 2023-09-01 09:04:48 +10:00
peteGSX
f40d57d8bd Add DCC type, EXTT broadcast from driver 2023-09-01 08:44:32 +10:00
peteGSX
9fa213e198 Undo callback 2023-08-31 13:51:25 +10:00
Harald Barth
b3cafd126e sample file corrections 2023-08-30 23:26:20 +02:00
peteGSX
a0c1ad182c Start on callback 2023-08-30 19:48:30 +10:00
peteGSX
dbf053858b Undo max params 2023-08-30 13:40:09 +10:00
peteGSX
232ac993ec Separate add from create 2023-08-30 08:45:11 +10:00
peteGSX
6cad794411 Working with 15 positions 2023-08-29 19:04:45 +10:00
peteGSX
b0d8510127 Working but limited 2023-08-29 13:38:52 +10:00
peteGSX
3bfdd16288 Start on JO 2023-08-28 13:11:37 +10:00
peteGSX
df4a501e8a Writing to driver 2023-08-28 08:36:09 +10:00
peteGSX
2202cb0c5e Minor progress 2023-08-27 19:30:56 +10:00
peteGSX
1425da20b5 Correct order 2023-08-26 19:41:17 +10:00
peteGSX
b823a647ac Some progress 2023-08-26 10:26:01 +10:00
Harald Barth
c55fa9f9d2 version number update 2023-08-25 19:08:58 +02:00
Harald Barth
210d96a3e3 Bugfix: ESP32 30ms off time 2023-08-25 19:07:57 +02:00
Harald Barth
42f3c7c128 version number update 2023-08-24 10:05:31 +02:00
Harald Barth
6cd7002e91 Bugfix: execute 30ms off time before rejoin 2023-08-24 10:03:29 +02:00
peteGSX
57d4655d54 Fix Uno/Nano build errors 2023-08-24 07:22:37 +10:00
peteGSX
ff9c558b61 Not much progress 2023-08-23 19:08:04 +10:00
peteGSX
b277d204f0 Progress! 2023-08-22 19:30:22 +10:00
peteGSX
c4febd1d0f More parser 2023-08-21 19:33:45 +10:00
peteGSX
98f8022268 Fix device driver, disable objects, start parser 2023-08-21 06:43:06 +10:00
peteGSX
1491da4813 Starting, very broken 2023-08-20 19:26:04 +10:00
peteGSX
085762e800 Add OPCODE list to DCCEXParser.cpp 2023-08-18 18:52:34 +10:00
pmantoine
e51f8e9c0a STM32 I2C Clock selection for 100/400KHz 2023-04-11 15:48:35 +08:00
Neil McKechnie
4f43a413b5 Update I2CManager_STM32.h
Remove debug code (writing to pin D2).  Update comments.  Restructure.
2023-03-30 18:30:38 +01:00
Neil McKechnie
4f56837d28 Fixes to timeout handling (due to STM32 micros() difference). 2023-03-28 18:07:52 +01:00
Neil McKechnie
cc2846d932 STM32 Native I2C first working version
Working for reads and writes, needs more testing and perhaps a polish.
2023-03-27 00:20:59 +01:00
pmantoine
83325ebf78 Initial I2C native driver 2023-03-23 08:44:25 +11:00
30 changed files with 2013 additions and 375 deletions

2
.gitignore vendored
View File

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

View File

@ -161,6 +161,10 @@ void CommandDistributor::broadcastTurnout(int16_t id, bool isClosed ) {
#endif
}
void CommandDistributor::broadcastTurntable(int16_t id, uint8_t position, bool moving) {
broadcastReply(COMMAND_TYPE, F("<I %d %d %d>\n"), id, position, moving);
}
void CommandDistributor::broadcastClockTime(int16_t time, int8_t rate) {
// The JMRI clock command is of the form : PFT65871<;>4
// The CS broadcast is of the form "<jC mmmm nn" where mmmm is time minutes and dd speed

View File

@ -49,6 +49,7 @@ public :
static void broadcastLoco(byte slot);
static void broadcastSensor(int16_t id, bool value);
static void broadcastTurnout(int16_t id, bool isClosed);
static void broadcastTurntable(int16_t id, uint8_t position, bool moving);
static void broadcastClockTime(int16_t time, int8_t rate);
static void setClockTime(int16_t time, int8_t rate, byte opt);
static int16_t retClockTime();

View File

@ -60,8 +60,8 @@ Once a new OPCODE is decided upon, update this list.
G,
h,
H, Turnout state broadcast
i, Reserved for future use - Turntable object broadcast
I, Reserved for future use - Turntable object command and control
i, Server details string
I, Turntable object command, control, and broadcast
j, Throttle responses
J, Throttle queries
k, Reserved for future use - Potentially Railcom
@ -114,6 +114,7 @@ Once a new OPCODE is decided upon, update this list.
#include "TrackManager.h"
#include "DCCTimer.h"
#include "EXRAIL2.h"
#include "Turntables.h"
// This macro can't be created easily as a portable function because the
// flashlist requires a far pointer for high flash access.
@ -121,7 +122,7 @@ Once a new OPCODE is decided upon, update this list.
for (int16_t i=0;;i+=sizeof(flashList[0])) { \
int16_t value=GETHIGHFLASHW(flashList,i); \
if (value==INT16_MAX) break; \
if (value != 0) StringFormatter::send(stream,F(" %d"),value); \
StringFormatter::send(stream,F(" %d"),value); \
}
@ -156,7 +157,10 @@ const int16_t HASH_KEYWORD_VPIN=-415;
const int16_t HASH_KEYWORD_A='A';
const int16_t HASH_KEYWORD_C='C';
const int16_t HASH_KEYWORD_G='G';
const int16_t HASH_KEYWORD_H='H';
const int16_t HASH_KEYWORD_I='I';
const int16_t HASH_KEYWORD_O='O';
const int16_t HASH_KEYWORD_P='P';
const int16_t HASH_KEYWORD_R='R';
const int16_t HASH_KEYWORD_T='T';
const int16_t HASH_KEYWORD_X='X';
@ -168,6 +172,8 @@ const int16_t HASH_KEYWORD_ANOUT = -26399;
const int16_t HASH_KEYWORD_WIFI = -5583;
const int16_t HASH_KEYWORD_ETHERNET = -30767;
const int16_t HASH_KEYWORD_WIT = 31594;
const int16_t HASH_KEYWORD_EXTT = 8573;
const int16_t HASH_KEYWORD_ADD = 3201;
int16_t DCCEXParser::stashP[MAX_COMMAND_PARAMS];
bool DCCEXParser::stashBusy;
@ -550,6 +556,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
bool main=false;
bool prog=false;
bool join=false;
bool singletrack=false;
//byte t=0;
if (params > 1) break;
if (params==0) { // All
main=true;
@ -569,20 +577,52 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
prog=true;
}
#endif
//else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H>
else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H>
byte t = (p[0] - 'A');
//DIAG(F("Processing track - %d "), t);
if (TrackManager::isProg(t)) {
main = false;
prog = true;
}
else
{
main=true;
prog=false;
}
singletrack=true;
if (main) TrackManager::setTrackPower(false, false, POWERMODE::ON, t);
if (prog) TrackManager::setTrackPower(true, false, POWERMODE::ON, t);
StringFormatter::send(stream, F("<1 %c>\n"), t+'A');
//CommandDistributor::broadcastPower();
//TrackManager::streamTrackState(NULL,t);
return;
}
else break; // will reply <X>
}
if (!singletrack) {
TrackManager::setJoin(join);
if (join) TrackManager::setJoinPower(POWERMODE::ON);
else {
if (main) TrackManager::setMainPower(POWERMODE::ON);
if (prog) TrackManager::setProgPower(POWERMODE::ON);
}
CommandDistributor::broadcastPower();
return;
}
}
case '0': // POWEROFF <0 [MAIN | PROG] >
{
bool main=false;
bool prog=false;
bool singletrack=false;
//byte t=0;
if (params > 1) break;
if (params==0) { // All
main=true;
@ -597,19 +637,47 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
prog=true;
}
#endif
//else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H>
else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H>
byte t = (p[0] - 'A');
//DIAG(F("Processing track - %d "), t);
if (TrackManager::isProg(t)) {
main = false;
prog = true;
}
else
{
main=true;
prog=false;
}
singletrack=true;
TrackManager::setJoin(false);
if (main) TrackManager::setTrackPower(false, false, POWERMODE::OFF, t);
if (prog) {
TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off
TrackManager::setTrackPower(true, false, POWERMODE::OFF, t);
}
StringFormatter::send(stream, F("<0 %c>\n"), t+'A');
//CommandDistributor::broadcastPower();
//TrackManager::streamTrackState(NULL, t);
return;
}
else break; // will reply <X>
}
if (!singletrack) {
TrackManager::setJoin(false);
if (main) TrackManager::setMainPower(POWERMODE::OFF);
if (prog) {
TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off
TrackManager::setProgPower(POWERMODE::OFF);
}
CommandDistributor::broadcastPower();
return;
}
}
case '!': // ESTOP ALL <!>
DCC::setThrottle(0,1,1); // this broadcasts speed 1(estop) and sets all reminders to speed 1.
@ -737,10 +805,14 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
SENDFLASHLIST(stream,RMFT2::rosterIdList)
}
else {
const FSH * functionNames= RMFT2::getRosterFunctions(id);
auto rosterName= RMFT2::getRosterName(id);
if (!rosterName) rosterName=F("");
auto functionNames= RMFT2::getRosterFunctions(id);
if (!functionNames) functionNames=RMFT2::getRosterFunctions(0);
if (!functionNames) functionNames=F("");
StringFormatter::send(stream,F(" %d \"%S\" \"%S\""),
id, RMFT2::getRosterName(id),
functionNames == NULL ? RMFT2::getRosterFunctions(0) : functionNames);
id, rosterName, functionNames);
}
#endif
StringFormatter::send(stream, F(">\n"));
@ -770,11 +842,70 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
}
StringFormatter::send(stream, F(">\n"));
return;
// No turntables without HAL support
#ifndef IO_NO_HAL
case HASH_KEYWORD_O: // <JO returns turntable list
StringFormatter::send(stream, F("<jO"));
if (params==1) { // <JO>
for (Turntable * tto=Turntable::first(); tto; tto=tto->next()) {
if (tto->isHidden()) continue;
StringFormatter::send(stream, F(" %d"),tto->getId());
}
StringFormatter::send(stream, F(">\n"));
} else { // <JO id>
Turntable *tto=Turntable::get(id);
if (!tto || tto->isHidden()) {
StringFormatter::send(stream, F(" %d X>\n"), id);
} else {
uint8_t pos = tto->getPosition();
uint8_t type = tto->isEXTT();
uint8_t posCount = tto->getPositionCount();
const FSH *todesc = NULL;
#ifdef EXRAIL_ACTIVE
todesc = RMFT2::getTurntableDescription(id);
#endif
if (todesc == NULL) todesc = F("");
StringFormatter::send(stream, F(" %d %d %d %d \"%S\">\n"), id, type, pos, posCount, todesc);
}
}
return;
case HASH_KEYWORD_P: // <JP id> returns turntable position list for the turntable id
if (params==2) { // <JP id>
Turntable *tto=Turntable::get(id);
if (!tto || tto->isHidden()) {
StringFormatter::send(stream, F(" %d X>\n"), id);
} else {
uint8_t posCount = tto->getPositionCount();
const FSH *tpdesc = NULL;
for (uint8_t p = 0; p < posCount; p++) {
StringFormatter::send(stream, F("<jP"));
int16_t angle = tto->getPositionAngle(p);
#ifdef EXRAIL_ACTIVE
tpdesc = RMFT2::getTurntablePositionDescription(id, p);
#endif
if (tpdesc == NULL) tpdesc = F("");
StringFormatter::send(stream, F(" %d %d %d \"%S\""), id, p, angle, tpdesc);
StringFormatter::send(stream, F(">\n"));
}
}
} else {
StringFormatter::send(stream, F("<jP X>\n"));
}
return;
#endif
default: break;
} // switch(p[1])
break; // case J
}
// No turntables without HAL support
#ifndef IO_NO_HAL
case 'I': // TURNTABLE <I ...>
if (parseI(stream, params, p))
return;
break;
#endif
case 'L': // LCC interface implemented in EXRAIL parser
break; // Will <X> if not intercepted by EXRAIL
@ -996,7 +1127,7 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
case HASH_KEYWORD_RAM: // <D RAM>
StringFormatter::send(stream, F("Free memory=%d\n"), DCCTimer::getMinimumFreeMemory());
break;
return true;
#ifndef DISABLE_PROG
case HASH_KEYWORD_ACK: // <D ACK ON/OFF> <D ACK [LIMIT|MIN|MAX|RETRY] Value>
@ -1097,6 +1228,99 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
return false;
}
// ==========================
// Turntable - no support if no HAL
// <I> - list all
// <I id> - broadcast type and current position
// <I id DCC> - create DCC - This is TBA
// <I id steps> - operate (DCC)
// <I id steps activity> - operate (EXTT)
// <I id ADD position value> - add position
// <I id EXTT i2caddress vpin home> - create EXTT
#ifndef IO_NO_HAL
bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[])
{
switch (params)
{
case 0: // <I> list turntable objects
return Turntable::printAll(stream);
case 1: // <I id> broadcast type and current position
{
Turntable *tto = Turntable::get(p[0]);
if (tto) {
bool type = tto->isEXTT();
uint8_t position = tto->getPosition();
StringFormatter::send(stream, F("<I %d %d>\n"), type, position);
} else {
return false;
}
}
return true;
case 2: // <I id position> - rotate a DCC turntable
{
Turntable *tto = Turntable::get(p[0]);
if (tto && !tto->isEXTT()) {
if (!tto->setPosition(p[0], p[1])) return false;
} else {
return false;
}
}
return true;
case 3: // <I id position activity> | <I id DCC home> - rotate to position for EX-Turntable or create DCC turntable
{
Turntable *tto = Turntable::get(p[0]);
if (p[1] == HASH_KEYWORD_DCC) {
if (tto || p[2] < 0 || p[2] > 3600) return false;
if (!DCCTurntable::create(p[0])) return false;
Turntable *tto = Turntable::get(p[0]);
tto->addPosition(0, 0, p[2]);
StringFormatter::send(stream, F("<I>\n"));
} else {
if (!tto) return false;
if (!tto->isEXTT()) return false;
if (!tto->setPosition(p[0], p[1], p[2])) return false;
}
}
return true;
case 4: // <I id EXTT vpin home> create an EXTT turntable
{
Turntable *tto = Turntable::get(p[0]);
if (p[1] == HASH_KEYWORD_EXTT) {
if (tto || p[3] < 0 || p[3] > 3600) return false;
if (!EXTTTurntable::create(p[0], (VPIN)p[2])) return false;
Turntable *tto = Turntable::get(p[0]);
tto->addPosition(0, 0, p[3]);
StringFormatter::send(stream, F("<I>\n"));
} else {
return false;
}
}
return true;
case 5: // <I id ADD position value angle> add a position
{
Turntable *tto = Turntable::get(p[0]);
if (p[1] == HASH_KEYWORD_ADD) {
// tto must exist, no more than 48 positions, angle 0 - 3600
if (!tto || p[2] > 48 || p[4] < 0 || p[4] > 3600) return false;
tto->addPosition(p[2], p[3], p[4]);
StringFormatter::send(stream, F("<I>\n"));
} else {
return false;
}
}
return true;
default: // Anything else is invalid
return false;
}
}
#endif
// CALLBACKS must be static
bool DCCEXParser::stashCallback(Print *stream, int16_t p[MAX_COMMAND_PARAMS], RingStream * ringStream)
{

View File

@ -24,6 +24,7 @@
#include <Arduino.h>
#include "FSH.h"
#include "RingStream.h"
#include "defines.h"
typedef void (*FILTER_CALLBACK)(Print * stream, byte & opcode, byte & paramCount, int16_t p[]);
typedef void (*AT_COMMAND_CALLBACK)(HardwareSerial * stream,const byte * command);
@ -49,6 +50,9 @@ struct DCCEXParser
static bool parseS(Print * stream, int16_t params, int16_t p[]);
static bool parsef(Print * stream, int16_t params, int16_t p[]);
static bool parseD(Print * stream, int16_t params, int16_t p[]);
#ifndef IO_NO_HAL
static bool parseI(Print * stream, int16_t params, int16_t p[]);
#endif
static Print * getAsyncReplyStream();
static void commitAsyncReplyStream();

View File

@ -125,8 +125,13 @@ private:
// On platforms that scan, it is called from waveform ISR
// only on a regular basis.
static void scan();
#if defined (ARDUINO_ARCH_STM32)
// bit array of used pins (max 32)
static uint32_t usedpins;
#else
// bit array of used pins (max 16)
static uint16_t usedpins;
#endif
static uint8_t highestPin;
// cached analog values (malloc:ed to actual number of ADC channels)
static int *analogvals;

View File

@ -1,6 +1,6 @@
/*
* © 2023 Neil McKechnie
* © 2022-23 Paul M. Antoine
* © 2022-2023 Paul M. Antoine
* © 2021 Mike S
* © 2021, 2023 Harald Barth
* © 2021 Fred Decker
@ -52,7 +52,7 @@ HardwareSerial Serial6(PA12, PA11); // Rx=PA12, Tx=PA11 -- CN10 pins 12 and 14
HardwareSerial Serial3(PC11, PC10); // Rx=PC11, Tx=PC10 -- USART3 - F446RE
HardwareSerial Serial5(PD2, PC12); // Rx=PC7, Tx=PC6 -- UART5 - F446RE
// On the F446RE, Serial4 and Serial6 also use pins we can't readily map while using the Arduino pins
#elif defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)|| defined(ARDUINO_NUCLEO_F412ZG)
#elif defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)
// Nucleo-144 boards don't have Serial1 defined by default
HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6
// Serial3 is defined to use USART3 by default, but is in fact used as the diag console
@ -154,13 +154,28 @@ HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6
///////////////////////////////////////////////////////////////////////////////////////////////
INTERRUPT_CALLBACK interruptHandler=0;
// Let's use STM32's timer #11 until disabused of this notion
// Timer #11 is used for "servo" library, but as DCC-EX is not using
// this libary, we should be free and clear.
HardwareTimer timer(TIM11);
// On STM32F4xx models that have them, Timers 6 and 7 have no PWM output capability,
// so are good choices for general timer duties - they are used for tone and servo
// in stm32duino so we shall usurp those as DCC-EX doesn't use tone or servo libs.
// NB: the F401, F410 and F411 do **not** have Timer 6 or 7, so we use Timer 11
#ifndef DCC_EX_TIMER
#if defined(TIM6)
#define DCC_EX_TIMER TIM6
#elif defined(TIM7)
#define DCC_EX_TIMER TIM7
#elif defined(TIM11)
#define DCC_EX_TIMER TIM11
#else
#warning This STM32F4XX variant does not have Timers 6,7 or 11!!
#endif
#endif // ifndef DCC_EX_TIMER
HardwareTimer dcctimer(DCC_EX_TIMER);
void DCCTimer_Handler() __attribute__((interrupt));
// Timer IRQ handler
void Timer11_Handler() {
void DCCTimer_Handler() {
interruptHandler();
}
@ -168,22 +183,24 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
interruptHandler=callback;
noInterrupts();
// adc_set_sample_rate(ADC_SAMPLETIME_480CYCLES);
timer.pause();
timer.setPrescaleFactor(1);
dcctimer.pause();
dcctimer.setPrescaleFactor(1);
// timer.setOverflow(CLOCK_CYCLES * 2);
timer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT);
timer.attachInterrupt(Timer11_Handler);
timer.refresh();
timer.resume();
dcctimer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT);
// dcctimer.attachInterrupt(Timer11_Handler);
dcctimer.attachInterrupt(DCCTimer_Handler);
dcctimer.setInterruptPriority(0, 0); // Set highest preemptive priority!
dcctimer.refresh();
dcctimer.resume();
interrupts();
}
bool DCCTimer::isPWMPin(byte pin) {
//TODO: SAMD whilst this call to digitalPinHasPWM will reveal which pins can do PWM,
//TODO: STM32 whilst this call to digitalPinHasPWM will reveal which pins can do PWM,
// there's no support yet for High Accuracy, so for now return false
// return digitalPinHasPWM(pin);
(void) pin;
return false;
}
@ -235,21 +252,90 @@ void DCCTimer::reset() {
while(true) {};
}
// TODO: may need to use uint32_t on STMF4xx variants with > 16 analog inputs!
#if defined(ARDUINO_NUCLEO_F446RE) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)
#warning STM32 board selected not fully supported - only use ADC1 inputs 0-15 for current sensing!
#endif
// For now, define the max of 16 ports - some variants have more, but this not **yet** supported
#define NUM_ADC_INPUTS 16
// #define NUM_ADC_INPUTS NUM_ANALOG_INPUTS
// TODO: rationalise the size of these... could really use sparse arrays etc.
static HardwareTimer * pin_timer[100] = {0};
static uint32_t channel_frequency[100] = {0};
static uint32_t pin_channel[100] = {0};
uint16_t ADCee::usedpins = 0;
uint8_t ADCee::highestPin = 0;
int * ADCee::analogvals = NULL;
uint32_t * analogchans = NULL;
bool adc1configured = false;
// Using the HardwareTimer library API included in stm32duino core to handle PWM duties
// TODO: in order to use the HA code above which Neil kindly wrote, we may have to do something more
// sophisticated about detecting any clash between the timer we'd like to use for PWM and the ones
// currently used for HA so they don't interfere with one another. For now we'll just make PWM
// work well... then work backwards to integrate with HA mode if we can.
void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency)
{
if (pin_timer[pin] == NULL) {
// Automatically retrieve TIM instance and channel associated to pin
// This is used to be compatible with all STM32 series automatically.
TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pin), PinMap_PWM);
if (Instance == NULL) {
// We shouldn't get here (famous last words) as it ought to have been caught by brakeCanPWM()!
DIAG(F("DCCEXanalogWriteFrequency::Pin %d has no PWM function!"), pin);
return;
}
pin_channel[pin] = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pin), PinMap_PWM));
int16_t ADCee::ADCmax() {
// Instantiate HardwareTimer object. Thanks to 'new' instantiation,
// HardwareTimer is not destructed when setup function is finished.
pin_timer[pin] = new HardwareTimer(Instance);
// Configure and start PWM
// MyTim->setPWM(channel, pin, 5, 10, NULL, NULL); // No callback required, we can simplify the function call
if (pin_timer[pin] != NULL)
{
pin_timer[pin]->setPWM(pin_channel[pin], pin, frequency, 0); // set frequency in Hertz, 0% dutycycle
DIAG(F("DCCEXanalogWriteFrequency::Pin %d on Timer %d, frequency %d"), pin, pin_channel[pin], frequency);
}
else
DIAG(F("DCCEXanalogWriteFrequency::failed to allocate HardwareTimer instance!"));
}
else
{
// Frequency change request
if (frequency != channel_frequency[pin])
{
pinmap_pinout(digitalPinToPinName(pin), PinMap_TIM); // ensure the pin has been configured!
pin_timer[pin]->setOverflow(frequency, HERTZ_FORMAT); // Just change the frequency if it's already running!
DIAG(F("DCCEXanalogWriteFrequency::setting frequency to %d"), frequency);
}
}
channel_frequency[pin] = frequency;
return;
}
void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
// Calculate percentage duty cycle from value given
uint32_t duty_cycle = (value * 100 / 256) + 1;
if (pin_timer[pin] != NULL) {
// if (duty_cycle == 100)
// {
// pin_timer[pin]->pauseChannel(pin_channel[pin]);
// DIAG(F("DCCEXanalogWrite::Pausing timer channel on pin %d"), pin);
// }
// else
// {
pinmap_pinout(digitalPinToPinName(pin), PinMap_TIM); // ensure the pin has been configured!
// pin_timer[pin]->resumeChannel(pin_channel[pin]);
pin_timer[pin]->setCaptureCompare(pin_channel[pin], duty_cycle, PERCENT_COMPARE_FORMAT); // DCC_EX_PWM_FREQ Hertz, duty_cycle% dutycycle
DIAG(F("DCCEXanalogWrite::Pin %d, value %d, duty cycle %d"), pin, value, duty_cycle);
// }
}
else
DIAG(F("DCCEXanalogWrite::Pin %d is not configured for PWM!"), pin);
}
// Now we can handle more ADCs, maybe this works!
#define NUM_ADC_INPUTS NUM_ANALOG_INPUTS
uint32_t ADCee::usedpins = 0; // Max of 32 ADC input channels!
uint8_t ADCee::highestPin = 0; // Highest pin to scan
int * ADCee::analogvals = NULL; // Array of analog values last captured
uint32_t * analogchans = NULL; // Array of channel numbers to be scanned
// bool adc1configured = false;
ADC_TypeDef * * adcchans = NULL; // Array to capture which ADC is each input channel on
int16_t ADCee::ADCmax()
{
return 4095;
}
@ -261,11 +347,33 @@ int ADCee::init(uint8_t pin) {
return -1024; // some silly value as error
uint32_t stmgpio = STM_PORT(stmpin); // converts to the GPIO port (16-bits per port group on STM32)
uint32_t adcchan = STM_PIN_CHANNEL(pinmap_function(stmpin, PinMap_ADC)); // find ADC channel (only valid for ADC1!)
GPIO_TypeDef * gpioBase;
uint32_t adcchan = STM_PIN_CHANNEL(pinmap_function(stmpin, PinMap_ADC)); // find ADC input channel
ADC_TypeDef *adc = (ADC_TypeDef *)pinmap_find_peripheral(stmpin, PinMap_ADC); // find which ADC this pin is on ADC1/2/3 etc.
int adcnum = 1;
if (adc == ADC1)
DIAG(F("ADCee::init(): found pin %d on ADC1"), pin);
// Checking for ADC2 and ADC3 being defined helps cater for more variants later
#if defined(ADC2)
else if (adc == ADC2)
{
DIAG(F("ADCee::init(): found pin %d on ADC2"), pin);
adcnum = 2;
}
#endif
#if defined(ADC3)
else if (adc == ADC3)
{
DIAG(F("ADCee::init(): found pin %d on ADC3"), pin);
adcnum = 3;
}
#endif
else DIAG(F("ADCee::init(): found pin %d on unknown ADC!"), pin);
// Port config - find which port we're on and power it up
switch(stmgpio) {
GPIO_TypeDef *gpioBase;
switch (stmgpio)
{
case 0x00:
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; //Power up PORTA
gpioBase = GPIOA;
@ -278,6 +386,20 @@ int ADCee::init(uint8_t pin) {
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN; //Power up PORTC
gpioBase = GPIOC;
break;
case 0x03:
RCC->AHB1ENR |= RCC_AHB1ENR_GPIODEN; //Power up PORTD
gpioBase = GPIOD;
break;
case 0x04:
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOEEN; //Power up PORTE
gpioBase = GPIOE;
break;
#if defined(GPIOF)
case 0x05:
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOFEN; //Power up PORTF
gpioBase = GPIOF;
break;
#endif
default:
return -1023; // some silly value as error
}
@ -293,31 +415,33 @@ int ADCee::init(uint8_t pin) {
if (adcchan > 18)
return -1022; // silly value as error
if (adcchan < 10)
ADC1->SMPR2 |= (0b111 << (adcchan * 3)); // Channel sampling rate 480 cycles
adc->SMPR2 |= (0b111 << (adcchan * 3)); // Channel sampling rate 480 cycles
else
ADC1->SMPR1 |= (0b111 << ((adcchan - 10) * 3)); // Channel sampling rate 480 cycles
adc->SMPR1 |= (0b111 << ((adcchan - 10) * 3)); // Channel sampling rate 480 cycles
// Read the inital ADC value for this analog input
ADC1->SQR3 = adcchan; // 1st conversion in regular sequence
ADC1->CR2 |= (1 << 30); // Start 1st conversion SWSTART
while(!(ADC1->SR & (1 << 1))); // Wait until conversion is complete
value = ADC1->DR; // Read value from register
adc->SQR3 = adcchan; // 1st conversion in regular sequence
adc->CR2 |= ADC_CR2_SWSTART; //(1 << 30); // Start 1st conversion SWSTART
while(!(adc->SR & (1 << 1))); // Wait until conversion is complete
value = adc->DR; // Read value from register
uint8_t id = pin - PNUM_ANALOG_BASE;
if (id > 15) { // today we have not enough bits in the mask to support more
return -1021;
}
// if (id > 15) { // today we have not enough bits in the mask to support more
// return -1021;
// }
if (analogvals == NULL) { // allocate analogvals and analogchans if this is the first invocation of init.
if (analogvals == NULL) { // allocate analogvals, analogchans and adcchans if this is the first invocation of init
analogvals = (int *)calloc(NUM_ADC_INPUTS+1, sizeof(int));
analogchans = (uint32_t *)calloc(NUM_ADC_INPUTS+1, sizeof(uint32_t));
adcchans = (ADC_TypeDef **)calloc(NUM_ADC_INPUTS+1, sizeof(ADC_TypeDef));
}
analogvals[id] = value; // Store sampled value
analogchans[id] = adcchan; // Keep track of which ADC channel is used for reading this pin
adcchans[id] = adc; // Keep track of which ADC this channel is on
usedpins |= (1 << id); // This pin is now ready
if (id > highestPin) highestPin = id; // Store our highest pin in use
DIAG(F("ADCee::init(): value=%d, channel=%d, id=%d"), value, adcchan, id);
DIAG(F("ADCee::init(): value=%d, ADC%d: channel=%d, id=%d"), value, adcnum, adcchan, id);
return value;
}
@ -344,13 +468,16 @@ void ADCee::scan() {
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 bool waiting = false;
static ADC_TypeDef *adc;
if (waiting) {
adc = adcchans[id];
if (waiting)
{
// look if we have a result
if (!(ADC1->SR & (1 << 1)))
if (!(adc->SR & (1 << 1)))
return; // no result, continue to wait
// found value
analogvals[id] = ADC1->DR;
analogvals[id] = adc->DR;
// advance at least one track
#ifdef DEBUG_ADC
if (id == 1) TrackManager::track[1]->setBrake(0);
@ -370,8 +497,9 @@ void ADCee::scan() {
while (true) {
if (mask & usedpins) {
// start new ADC aquire on id
ADC1->SQR3 = analogchans[id]; //1st conversion in regular sequence
ADC1->CR2 |= (1 << 30); //Start 1st conversion SWSTART
adc = adcchans[id];
adc->SQR3 = analogchans[id]; // 1st conversion in regular sequence
adc->CR2 |= (1 << 30); // Start 1st conversion SWSTART
#ifdef DEBUG_ADC
if (id == 1) TrackManager::track[1]->setBrake(1);
#endif
@ -392,19 +520,83 @@ void ADCee::scan() {
void ADCee::begin() {
noInterrupts();
//ADC1 config sequence
// TODO: currently defaults to ADC1, may need more to handle other members of STM32F4xx family
RCC->APB2ENR |= (1 << 8); //Enable ADC1 clock (Bit8)
RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; // Enable ADC1 clock
// Set ADC prescaler - DIV8 ~ 40ms, DIV6 ~ 30ms, DIV4 ~ 20ms, DIV2 ~ 11ms
ADC->CCR = (0 << 16); // Set prescaler 0=DIV2, 1=DIV4, 2=DIV6, 3=DIV8
ADC1->CR1 &= ~(1 << 8); //SCAN mode disabled (Bit8)
ADC1->CR1 &= ~(3 << 24); //12bit resolution (Bit24,25 0b00)
ADC1->SQR1 = (1 << 20); //Set number of conversions projected (L[3:0] 0b0001) -> 1 conversion
// Disable the DMA controller for ADC1
ADC1->CR2 &= ~ADC_CR2_DMA;
ADC1->CR2 &= ~(1 << 1); //Single conversion
ADC1->CR2 &= ~(1 << 11); //Right alignment of data bits bit12....bit0
ADC1->SQR1 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register
ADC1->SQR2 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register
ADC1->SQR3 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register
ADC1->CR2 |= (1 << 0); // Switch on ADC1
// Wait for ADC1 to become ready (calibration complete)
while (!(ADC1->CR2 & ADC_CR2_ADON)) {
}
#if defined(ADC2)
// Enable the ADC2 clock
RCC->APB2ENR |= RCC_APB2ENR_ADC2EN;
// Initialize ADC2
ADC2->CR1 = 0; // Disable all channels
ADC2->CR2 = 0; // Clear CR2 register
ADC2->CR1 &= ~(1 << 8); //SCAN mode disabled (Bit8)
ADC2->CR1 &= ~(3 << 24); //12bit resolution (Bit24,25 0b00)
ADC2->SQR1 = (1 << 20); //Set number of conversions projected (L[3:0] 0b0001) -> 1 conversion
ADC2->CR2 &= ~ADC_CR2_DMA; // Disable the DMA controller for ADC3
ADC2->CR2 &= ~(1 << 1); //Single conversion
ADC2->CR2 &= ~(1 << 11); //Right alignment of data bits bit12....bit0
ADC2->SQR1 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register
ADC2->SQR2 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register
ADC2->SQR3 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register
// Enable the ADC
ADC2->CR2 |= ADC_CR2_ADON;
// Wait for ADC2 to become ready (calibration complete)
while (!(ADC2->CR2 & ADC_CR2_ADON)) {
}
// Perform ADC3 calibration (optional)
// ADC3->CR2 |= ADC_CR2_CAL;
// while (ADC3->CR2 & ADC_CR2_CAL) {
// }
#endif
#if defined(ADC3)
// Enable the ADC3 clock
RCC->APB2ENR |= RCC_APB2ENR_ADC3EN;
// Initialize ADC3
ADC3->CR1 = 0; // Disable all channels
ADC3->CR2 = 0; // Clear CR2 register
ADC3->CR1 &= ~(1 << 8); //SCAN mode disabled (Bit8)
ADC3->CR1 &= ~(3 << 24); //12bit resolution (Bit24,25 0b00)
ADC3->SQR1 = (1 << 20); //Set number of conversions projected (L[3:0] 0b0001) -> 1 conversion
ADC3->CR2 &= ~ADC_CR2_DMA; // Disable the DMA controller for ADC3
ADC3->CR2 &= ~(1 << 1); //Single conversion
ADC3->CR2 &= ~(1 << 11); //Right alignment of data bits bit12....bit0
ADC3->SQR1 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register
ADC3->SQR2 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register
ADC3->SQR3 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register
// Enable the ADC
ADC3->CR2 |= ADC_CR2_ADON;
// Wait for ADC3 to become ready (calibration complete)
while (!(ADC3->CR2 & ADC_CR2_ADON)) {
}
// Perform ADC3 calibration (optional)
// ADC3->CR2 |= ADC_CR2_CAL;
// while (ADC3->CR2 & ADC_CR2_CAL) {
// }
#endif
interrupts();
}
#endif

View File

@ -52,6 +52,8 @@
#include "Turnouts.h"
#include "CommandDistributor.h"
#include "TrackManager.h"
#include "Turntables.h"
#include "IODevice.h"
// Command parsing keywords
const int16_t HASH_KEYWORD_EXRAIL=15435;
@ -97,6 +99,9 @@ LookList * RMFT2::onAmberLookup=NULL;
LookList * RMFT2::onGreenLookup=NULL;
LookList * RMFT2::onChangeLookup=NULL;
LookList * RMFT2::onClockLookup=NULL;
#ifndef IO_NO_HAL
LookList * RMFT2::onRotateLookup=NULL;
#endif
LookList * RMFT2::onOverloadLookup=NULL;
#define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter)
@ -176,6 +181,9 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
onDeactivateLookup=LookListLoader(OPCODE_ONDEACTIVATE);
onChangeLookup=LookListLoader(OPCODE_ONCHANGE);
onClockLookup=LookListLoader(OPCODE_ONTIME);
#ifndef IO_NO_HAL
onRotateLookup=LookListLoader(OPCODE_ONROTATE);
#endif
onOverloadLookup=LookListLoader(OPCODE_ONOVERLOAD);
// onLCCLookup is not the same so not loaded here.
@ -248,6 +256,37 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
break;
}
#ifndef IO_NO_HAL
case OPCODE_DCCTURNTABLE: {
VPIN id=operand;
int home=getOperand(progCounter,1);
setTurntableHiddenState(DCCTurntable::create(id));
Turntable *tto=Turntable::get(id);
tto->addPosition(0,0,home);
break;
}
case OPCODE_EXTTTURNTABLE: {
VPIN id=operand;
VPIN pin=getOperand(progCounter,1);
int home=getOperand(progCounter,3);
setTurntableHiddenState(EXTTTurntable::create(id,pin));
Turntable *tto=Turntable::get(id);
tto->addPosition(0,0,home);
break;
}
case OPCODE_TTADDPOSITION: {
VPIN id=operand;
int position=getOperand(progCounter,1);
int value=getOperand(progCounter,2);
int angle=getOperand(progCounter,3);
Turntable *tto=Turntable::get(id);
tto->addPosition(position,value,angle);
break;
}
#endif
case OPCODE_AUTOSTART:
// automatically create a task from here at startup.
// Removed if (progCounter>0) check 4.2.31 because
@ -272,6 +311,12 @@ void RMFT2::setTurnoutHiddenState(Turnout * t) {
t->setHidden(GETFLASH(getTurnoutDescription(t->getId()))==0x01);
}
#ifndef IO_NO_HAL
void RMFT2::setTurntableHiddenState(Turntable * tto) {
tto->setHidden(GETFLASH(getTurntableDescription(tto->getId()))==0x01);
}
#endif
char RMFT2::getRouteType(int16_t id) {
for (int16_t i=0;;i+=2) {
int16_t rid= GETHIGHFLASHW(routeIdList,i);
@ -664,6 +709,14 @@ void RMFT2::loop2() {
Turnout::setClosed(operand, true);
break;
#ifndef IO_NO_HAL
case OPCODE_ROTATE:
uint8_t activity;
activity=getOperand(2);
Turntable::setPosition(operand,getOperand(1),activity);
break;
#endif
case OPCODE_REV:
forward = false;
driveLoco(operand);
@ -791,6 +844,20 @@ void RMFT2::loop2() {
CommandDistributor::broadcastPower();
break;
case OPCODE_SET_POWER:
// operand is TRACK_POWER , trackid
//byte thistrack=getOperand(1);
switch (operand) {
case TRACK_POWER_0:
TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), false, POWERMODE::OFF, getOperand(1));
break;
case TRACK_POWER_1:
TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), false, POWERMODE::ON, getOperand(1));
break;
}
break;
case OPCODE_SET_TRACK:
// operand is trackmode<<8 | track id
// If DC/DCX use my loco for DC address
@ -864,6 +931,12 @@ void RMFT2::loop2() {
skipIf=Turnout::isThrown(operand);
break;
#ifndef IO_NO_HAL
case OPCODE_IFTTPOSITION: // do block if turntable at this position
skipIf=Turntable::getPosition(operand)!=(int)getOperand(1);
break;
#endif
case OPCODE_ENDIF:
break;
@ -1051,6 +1124,15 @@ void RMFT2::loop2() {
}
break;
#ifndef IO_NO_HAL
case OPCODE_WAITFORTT: // OPCODE_WAITFOR,V(turntable_id)
if (Turntable::ttMoving(operand)) {
delayMe(100);
return;
}
break;
#endif
case OPCODE_PRINT:
printMessage(operand);
break;
@ -1076,6 +1158,12 @@ void RMFT2::loop2() {
case OPCODE_ONGREEN:
case OPCODE_ONCHANGE:
case OPCODE_ONTIME:
#ifndef IO_NO_HAL
case OPCODE_DCCTURNTABLE: // Turntable definition ignored at runtime
case OPCODE_EXTTTURNTABLE: // Turntable definition ignored at runtime
case OPCODE_TTADDPOSITION: // Turntable position definition ignored at runtime
case OPCODE_ONROTATE:
#endif
case OPCODE_ONOVERLOAD:
break;
@ -1199,7 +1287,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
}
/* static */ bool RMFT2::isSignal(int16_t id,char rag) {
if (!(compileFeatures & FEATURE_LCC)) return false;
if (!(compileFeatures & FEATURE_SIGNAL)) return false;
int16_t sigslot=getSignalSlot(id);
if (sigslot<0) return false;
return (flags[sigslot] & SIGNAL_MASK) == rag;
@ -1223,6 +1311,13 @@ void RMFT2::changeEvent(int16_t vpin, bool change) {
if (change) handleEvent(F("CHANGE"),onChangeLookup,vpin);
}
#ifndef IO_NO_HAL
void RMFT2::rotateEvent(int16_t turntableId, bool change) {
// Hunt or an ONROTATE for this turntable
if (change) handleEvent(F("ROTATE"),onRotateLookup,turntableId);
}
#endif
void RMFT2::clockEvent(int16_t clocktime, bool change) {
// Hunt for an ONTIME for this time
if (Diag::CMD)

View File

@ -25,6 +25,7 @@
#include "FSH.h"
#include "IODevice.h"
#include "Turnouts.h"
#include "Turntables.h"
// The following are the operation codes (or instructions) for a kind of virtual machine.
// Each instruction is normally 3 bytes long with an operation code followed by a parameter.
@ -58,11 +59,13 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,
OPCODE_ROSTER,OPCODE_KILLALL,
OPCODE_ROUTE,OPCODE_AUTOMATION,OPCODE_SEQUENCE,
OPCODE_ENDTASK,OPCODE_ENDEXRAIL,
OPCODE_SET_TRACK,
OPCODE_SET_TRACK,OPCODE_SET_POWER,
OPCODE_ONRED,OPCODE_ONAMBER,OPCODE_ONGREEN,
OPCODE_ONCHANGE,
OPCODE_ONCLOCKTIME,
OPCODE_ONTIME,
OPCODE_TTADDPOSITION,OPCODE_DCCTURNTABLE,OPCODE_EXTTTURNTABLE,
OPCODE_ONROTATE,OPCODE_ROTATE,OPCODE_WAITFORTT,
OPCODE_LCC,OPCODE_LCCX,OPCODE_ONLCC,
OPCODE_ONOVERLOAD,
@ -77,7 +80,8 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,
OPCODE_IFRANDOM,OPCODE_IFRESERVE,
OPCODE_IFCLOSED,OPCODE_IFTHROWN,
OPCODE_IFRE,
OPCODE_IFLOCO
OPCODE_IFLOCO,
OPCODE_IFTTPOSITION
};
// Ensure thrunge_lcd is put last as there may be more than one display,
@ -91,9 +95,10 @@ enum thrunger: byte {
thrunge_lcd, // Must be last!!
};
// Flag bits for compile time feature
// Flag bits for compile time features.
static const byte FEATURE_SIGNAL= 0x80;
static const byte FEATURE_LCC = 0x40;
static const byte FEATURE_ROSTER= 0x20;
// Flag bits for status of hardware and TPL
@ -136,6 +141,7 @@ class LookList {
static void activateEvent(int16_t addr, bool active);
static void changeEvent(int16_t id, bool change);
static void clockEvent(int16_t clocktime, bool change);
static void rotateEvent(int16_t id, bool change);
static void powerEvent(int16_t track, bool overload);
static const int16_t SERVO_SIGNAL_FLAG=0x4000;
static const int16_t ACTIVE_HIGH_SIGNAL_FLAG=0x2000;
@ -151,6 +157,8 @@ class LookList {
static const FSH * getTurnoutDescription(int16_t id);
static const FSH * getRosterName(int16_t id);
static const FSH * getRosterFunctions(int16_t id);
static const FSH * getTurntableDescription(int16_t id);
static const FSH * getTurntablePositionDescription(int16_t turntableId, uint8_t positionId);
private:
static void ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]);
@ -163,6 +171,9 @@ private:
static bool isSignal(int16_t id,char rag);
static int16_t getSignalSlot(int16_t id);
static void setTurnoutHiddenState(Turnout * t);
#ifndef IO_NO_HAL
static void setTurntableHiddenState(Turntable * tto);
#endif
static LookList* LookListLoader(OPCODE op1,
OPCODE op2=OPCODE_ENDEXRAIL,OPCODE op3=OPCODE_ENDEXRAIL);
static void handleEvent(const FSH* reason,LookList* handlers, int16_t id);
@ -197,6 +208,9 @@ private:
static LookList * onGreenLookup;
static LookList * onChangeLookup;
static LookList * onClockLookup;
#ifndef IO_NO_HAL
static LookList * onRotateLookup;
#endif
static LookList * onOverloadLookup;
static const int countLCCLookup;

View File

@ -41,6 +41,7 @@
#undef CALL
#undef CLOSE
#undef DCC_SIGNAL
#undef DCC_TURNTABLE
#undef DEACTIVATE
#undef DEACTIVATEL
#undef DELAY
@ -54,6 +55,7 @@
#undef ENDTASK
#undef ESTOP
#undef EXRAIL
#undef EXTT_TURNTABLE
#undef FADE
#undef FOFF
#undef FOLLOW
@ -76,6 +78,7 @@
#undef IFRESERVE
#undef IFTHROWN
#undef IFTIMEOUT
#undef IFTTPOSITION
#undef IFRE
#undef INVERT_DIRECTION
#undef JOIN
@ -100,6 +103,7 @@
#undef ONOVERLOAD
#undef ONGREEN
#undef ONRED
#undef ONROTATE
#undef ONTHROW
#undef ONCHANGE
#undef PARSE
@ -119,6 +123,8 @@
#undef RETURN
#undef REV
#undef ROSTER
#undef ROTATE
#undef ROTATE_DCC
#undef ROUTE
#undef SENDLOCO
#undef SEQUENCE
@ -135,6 +141,7 @@
#undef SERVO_SIGNAL
#undef SET
#undef SET_TRACK
#undef SET_POWER
#undef SETLOCO
#undef SIGNAL
#undef SIGNALH
@ -142,6 +149,7 @@
#undef START
#undef STOP
#undef THROW
#undef TT_ADDPOSITION
#undef TURNOUT
#undef TURNOUTL
#undef UNJOIN
@ -149,6 +157,9 @@
#undef VIRTUAL_SIGNAL
#undef VIRTUAL_TURNOUT
#undef WAITFOR
#ifndef IO_NO_HAL
#undef WAITFORTT
#endif
#undef WITHROTTLE
#undef XFOFF
#undef XFON
@ -171,6 +182,7 @@
#define CALL(route)
#define CLOSE(id)
#define DCC_SIGNAL(id,add,subaddr)
#define DCC_TURNTABLE(id,home,description)
#define DEACTIVATE(addr,subaddr)
#define DEACTIVATEL(addr)
#define DELAY(mindelay)
@ -184,6 +196,7 @@
#define ENDTASK
#define ESTOP
#define EXRAIL
#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description)
#define FADE(pin,value,ms)
#define FOFF(func)
#define FOLLOW(route)
@ -206,6 +219,7 @@
#define IFTHROWN(turnout_id)
#define IFRESERVE(block)
#define IFTIMEOUT
#define IFTTPOSITION(turntable_id,position)
#define IFRE(sensor_id,value)
#define INVERT_DIRECTION
#define JOIN
@ -230,6 +244,7 @@
#define ONLCC(sender,event)
#define ONGREEN(signal_id)
#define ONRED(signal_id)
#define ONROTATE(turntable_id)
#define ONTHROW(turnout_id)
#define ONCHANGE(sensor_id)
#define PAUSE
@ -248,8 +263,10 @@
#define RESUME
#define RETURN
#define REV(speed)
#define ROUTE(id,description)
#define ROTATE(turntable_id,position,activity)
#define ROTATE_DCC(turntable_id,position)
#define ROSTER(cab,name,funcmap...)
#define ROUTE(id,description)
#define SENDLOCO(cab,route)
#define SEQUENCE(id)
#define SERIAL(msg)
@ -265,6 +282,7 @@
#define SERVO_TURNOUT(id,pin,activeAngle,inactiveAngle,profile,description...)
#define SET(pin)
#define SET_TRACK(track,mode)
#define SET_POWER(track,onoff)
#define SETLOCO(loco)
#define SIGNAL(redpin,amberpin,greenpin)
#define SIGNALH(redpin,amberpin,greenpin)
@ -272,6 +290,7 @@
#define START(route)
#define STOP
#define THROW(id)
#define TT_ADDPOSITION(turntable_id,position,value,angle,description...)
#define TURNOUT(id,addr,subaddr,description...)
#define TURNOUTL(id,addr,description...)
#define UNJOIN
@ -279,6 +298,9 @@
#define VIRTUAL_SIGNAL(id)
#define VIRTUAL_TURNOUT(id,description...)
#define WAITFOR(pin)
#ifndef IO_NO_HAL
#define WAITFORTT(turntable_id)
#endif
#define WITHROTTLE(msg)
#define XFOFF(cab,func)
#define XFON(cab,func)

View File

@ -54,6 +54,8 @@
// helper macro for turnout descriptions, creates NULL for missing description
#define O_DESC(id, desc) case id: return ("" desc)[0]?F("" desc):NULL;
// helper macro for turntable descriptions, creates NULL for missing description
#define T_DESC(tid,pid,desc) if(turntableId==tid && positionId==pid) return ("" desc)[0]?F("" desc):NULL;
// helper macro for turnout description as HIDDEN
#define HIDDEN "\x01"
@ -61,6 +63,11 @@
// (10#mins)%100)
#define STRIP_ZERO(value) 10##value%100
// These constants help EXRAIL macros convert Track Power e.g. SET_POWER(A ON|OFF).
//const byte TRACK_POWER_0=0, TRACK_POWER_OFF=0;
//const byte TRACK_POWER_1=1, TRACK_POWER_ON=1;
// Pass 1 Implements aliases
#include "EXRAIL2MacroReset.h"
#undef ALIAS
@ -68,9 +75,12 @@
#include "myAutomation.h"
// Pass 1h Implements HAL macro by creating exrailHalSetup function
// Also allows creating EXTurntable object
#include "EXRAIL2MacroReset.h"
#undef HAL
#define HAL(haltype,params...) haltype::create(params);
#undef EXTT_TURNTABLE
#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description...) EXTurntable::create(vpin,1,i2c_address);
void exrailHalSetup() {
#include "myAutomation.h"
}
@ -211,6 +221,31 @@ const FSH * RMFT2::getTurnoutDescription(int16_t turnoutid) {
return NULL;
}
// Pass to get turntable descriptions (optional)
#include "EXRAIL2MacroReset.h"
#undef DCC_TURNTABLE
#define DCC_TURNTABLE(id,home,description...) O_DESC(id,description)
#undef EXTT_TURNTABLE
#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description...) O_DESC(id,description)
const FSH * RMFT2::getTurntableDescription(int16_t turntableId) {
switch (turntableId) {
#include "myAutomation.h"
default:break;
}
return NULL;
}
// Pass to get turntable position descriptions (optional)
#include "EXRAIL2MacroReset.h"
#undef TT_ADDPOSITION
#define TT_ADDPOSITION(turntable_id,position,value,home,description...) T_DESC(turntable_id,position,description)
const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) {
#include "myAutomation.h"
return NULL;
}
// Pass 6: Roster IDs (count)
#include "EXRAIL2MacroReset.h"
#undef ROSTER
@ -303,6 +338,9 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define BROADCAST(msg) PRINT(msg)
#define CALL(route) OPCODE_CALL,V(route),
#define CLOSE(id) OPCODE_CLOSE,V(id),
#ifndef IO_NO_HAL
#define DCC_TURNTABLE(id,home,description...) OPCODE_DCCTURNTABLE,V(id),OPCODE_PAD,V(home),
#endif
#define DEACTIVATE(addr,subaddr) OPCODE_DCCACTIVATE,V(addr<<3 | subaddr<<1),
#define DEACTIVATEL(addr) OPCODE_DCCACTIVATE,V((addr+3)<<1),
#define DELAY(ms) ms<30000?OPCODE_DELAYMS:OPCODE_DELAY,V(ms/(ms<30000?1L:100L)),
@ -317,6 +355,9 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define ENDTASK OPCODE_ENDTASK,0,0,
#define ESTOP OPCODE_SPEED,V(1),
#define EXRAIL
#ifndef IO_NO_HAL
#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description...) OPCODE_EXTTTURNTABLE,V(id),OPCODE_PAD,V(vpin),OPCODE_PAD,V(i2c_address),OPCODE_PAD,V(home),
#endif
#define FADE(pin,value,ms) OPCODE_SERVO,V(pin),OPCODE_PAD,V(value),OPCODE_PAD,V(PCA9685::ProfileType::UseDuration|PCA9685::NoPowerOff),OPCODE_PAD,V(ms/100L),
#define FOFF(func) OPCODE_FOFF,V(func),
#define FOLLOW(route) OPCODE_FOLLOW,V(route),
@ -339,6 +380,9 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define IFRESERVE(block) OPCODE_IFRESERVE,V(block),
#define IFTHROWN(turnout_id) OPCODE_IFTHROWN,V(turnout_id),
#define IFTIMEOUT OPCODE_IFTIMEOUT,0,0,
#ifndef IO_NO_HAL
#define IFTTPOSITION(id,position) OPCODE_IFTTPOSITION,V(id),OPCODE_PAD,V(position),
#endif
#define IFRE(sensor_id,value) OPCODE_IFRE,V(sensor_id),OPCODE_PAD,V(value),
#define INVERT_DIRECTION OPCODE_INVERT_DIRECTION,0,0,
#define JOIN OPCODE_JOIN,0,0,
@ -369,6 +413,9 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define ONDEACTIVATEL(linear) OPCODE_ONDEACTIVATE,V(linear+3),
#define ONGREEN(signal_id) OPCODE_ONGREEN,V(signal_id),
#define ONRED(signal_id) OPCODE_ONRED,V(signal_id),
#ifndef IO_NO_HAL
#define ONROTATE(id) OPCODE_ONROTATE,V(id),
#endif
#define ONTHROW(turnout_id) OPCODE_ONTHROW,V(turnout_id),
#define ONCHANGE(sensor_id) OPCODE_ONCHANGE,V(sensor_id),
#define PAUSE OPCODE_PAUSE,0,0,
@ -388,6 +435,10 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define RETURN OPCODE_RETURN,0,0,
#define REV(speed) OPCODE_REV,V(speed),
#define ROSTER(cabid,name,funcmap...)
#ifndef IO_NO_HAL
#define ROTATE(id,position,activity) OPCODE_ROTATE,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(EXTurntable::activity),
#define ROTATE_DCC(id,position) OPCODE_ROTATE,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(0),
#endif
#define ROUTE(id, description) OPCODE_ROUTE, V(id),
#define SENDLOCO(cab,route) OPCODE_SENDLOCO,V(cab),OPCODE_PAD,V(route),
#define SEQUENCE(id) OPCODE_SEQUENCE, V(id),
@ -404,6 +455,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define SERVO_TURNOUT(id,pin,activeAngle,inactiveAngle,profile,description...) OPCODE_SERVOTURNOUT,V(id),OPCODE_PAD,V(pin),OPCODE_PAD,V(activeAngle),OPCODE_PAD,V(inactiveAngle),OPCODE_PAD,V(PCA9685::ProfileType::profile),
#define SET(pin) OPCODE_SET,V(pin),
#define SET_TRACK(track,mode) OPCODE_SET_TRACK,V(TRACK_MODE_##mode <<8 | TRACK_NUMBER_##track),
#define SET_POWER(track,onoff) OPCODE_SET_POWER,V(TRACK_POWER_##onoff),OPCODE_PAD, V(TRACK_NUMBER_##track),
#define SETLOCO(loco) OPCODE_SETLOCO,V(loco),
#define SIGNAL(redpin,amberpin,greenpin)
#define SIGNALH(redpin,amberpin,greenpin)
@ -411,6 +463,9 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define START(route) OPCODE_START,V(route),
#define STOP OPCODE_SPEED,V(0),
#define THROW(id) OPCODE_THROW,V(id),
#ifndef IO_NO_HAL
#define TT_ADDPOSITION(id,position,value,angle,description...) OPCODE_TTADDPOSITION,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(value),OPCODE_PAD,V(angle),
#endif
#define TURNOUT(id,addr,subaddr,description...) OPCODE_TURNOUT,V(id),OPCODE_PAD,V(addr),OPCODE_PAD,V(subaddr),
#define TURNOUTL(id,addr,description...) TURNOUT(id,(addr-1)/4+1,(addr-1)%4, description)
#define UNJOIN OPCODE_UNJOIN,0,0,
@ -419,6 +474,9 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define VIRTUAL_TURNOUT(id,description...) OPCODE_PINTURNOUT,V(id),OPCODE_PAD,V(0),
#define WITHROTTLE(msg) PRINT(msg)
#define WAITFOR(pin) OPCODE_WAITFOR,V(pin),
#ifndef IO_NO_HAL
#define WAITFORTT(turntable_id) OPCODE_WAITFORTT,V(turntable_id),
#endif
#define XFOFF(cab,func) OPCODE_XFOFF,V(cab),OPCODE_PAD,V(func),
#define XFON(cab,func) OPCODE_XFON,V(cab),OPCODE_PAD,V(func),

View File

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

View File

@ -92,7 +92,7 @@ void I2CManagerClass::begin(void) {
// Probe and list devices. Use standard mode
// (clock speed 100kHz) for best device compatibility.
_setClock(100000);
unsigned long originalTimeout = _timeout;
uint32_t originalTimeout = _timeout;
setTimeout(1000); // use 1ms timeout for probes
#if defined(I2C_EXTENDED_ADDRESS)

View File

@ -485,7 +485,7 @@ private:
// When retries are enabled, the timeout applies to each
// try, and failure from timeout does not get retried.
// A value of 0 means disable timeout monitoring.
unsigned long _timeout = 100000UL;
uint32_t _timeout = 100000UL;
// Finish off request block by waiting for completion and posting status.
uint8_t finishRB(I2CRB *rb, uint8_t status);
@ -532,13 +532,14 @@ private:
uint8_t bytesToSend = 0;
uint8_t bytesToReceive = 0;
uint8_t operation = 0;
unsigned long startTime = 0;
uint32_t startTime = 0;
uint8_t muxPhase = 0;
uint8_t muxAddress = 0;
uint8_t muxData[1];
uint8_t deviceAddress;
const uint8_t *sendBuffer;
uint8_t *receiveBuffer;
uint8_t transactionState = 0;
volatile uint32_t pendingClockSpeed = 0;

View File

@ -172,6 +172,10 @@ void I2CManagerClass::startTransaction() {
* Function to queue a request block and initiate operations.
***************************************************************************/
void I2CManagerClass::queueRequest(I2CRB *req) {
if (((req->operation & OPERATION_MASK) == OPERATION_READ) && req->readLen == 0)
return; // Ignore null read
req->status = I2C_STATUS_PENDING;
req->nextRequest = NULL;
ATOMIC_BLOCK() {
@ -184,6 +188,7 @@ void I2CManagerClass::queueRequest(I2CRB *req) {
}
/***************************************************************************
* Initiate a write to an I2C device (non-blocking operation)
***************************************************************************/
@ -240,8 +245,8 @@ void I2CManagerClass::checkForTimeout() {
I2CRB *t = queueHead;
if (state==I2C_STATE_ACTIVE && t!=0 && t==currentRequest && _timeout > 0) {
// Check for timeout
unsigned long elapsed = micros() - startTime;
if (elapsed > _timeout) {
int32_t elapsed = micros() - startTime;
if (elapsed > (int32_t)_timeout) {
#ifdef DIAG_IO
//DIAG(F("I2CManager Timeout on %s"), t->i2cAddress.toString());
#endif
@ -300,12 +305,12 @@ void I2CManagerClass::handleInterrupt() {
// Check if current request has completed. If there's a current request
// and state isn't active then state contains the completion status of the request.
if (state == I2C_STATE_COMPLETED && currentRequest != NULL) {
if (state == I2C_STATE_COMPLETED && currentRequest != NULL && currentRequest == queueHead) {
// Operation has completed.
if (completionStatus == I2C_STATUS_OK || ++retryCounter > MAX_I2C_RETRIES
|| currentRequest->operation & OPERATION_NORETRY)
{
// Status is OK, or has failed and retry count exceeded, or retries disabled.
// Status is OK, or has failed and retry count exceeded, or failed and retries disabled.
#if defined(I2C_EXTENDED_ADDRESS)
if (muxPhase == MuxPhase_PROLOG ) {
overallStatus = completionStatus;

View File

@ -26,27 +26,44 @@
#include "I2CManager.h"
#include "I2CManager_NonBlocking.h" // to satisfy intellisense
//#include <avr/io.h>
//#include <avr/interrupt.h>
#include <wiring_private.h>
#include "stm32f4xx_hal_rcc.h"
/***************************************************************************
* Interrupt handler.
* IRQ handler for SERCOM3 which is the default I2C definition for Arduino Zero
* compatible variants such as the Sparkfun SAMD21 Dev Breakout etc.
* Later we may wish to allow use of an alternate I2C bus, or more than one I2C
* bus on the SAMD architecture
***************************************************************************/
/*****************************************************************************
* STM32F4xx I2C native driver support
*
* Nucleo-64 and Nucleo-144 boards all use I2C1 as the default I2C peripheral
* Later we may wish to support other STM32 boards, allow use of an alternate
* I2C bus, or more than one I2C bus on the STM32 architecture
*****************************************************************************/
#if defined(I2C_USE_INTERRUPTS) && defined(ARDUINO_ARCH_STM32)
void I2C1_IRQHandler() {
#if defined(ARDUINO_NUCLEO_F401RE) || defined(ARDUINO_NUCLEO_F411RE) || defined(ARDUINO_NUCLEO_F446RE) \
|| defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F413ZH) \
|| defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)
// Assume I2C1 for now - default I2C bus on Nucleo-F411RE and likely all Nucleo-64
// and Nucleo-144 variants
I2C_TypeDef *s = I2C1;
// In init we will ask the STM32 HAL layer for the configured APB1 clock frequency in Hz
uint32_t APB1clk1; // Peripheral Input Clock speed in Hz.
uint32_t i2c_MHz; // Peripheral Input Clock speed in MHz.
// IRQ handler for I2C1, replacing the weak definition in the STM32 HAL
extern "C" void I2C1_EV_IRQHandler(void) {
I2CManager.handleInterrupt();
}
extern "C" void I2C1_ER_IRQHandler(void) {
I2CManager.handleInterrupt();
}
#else
#warning STM32 board selected is not yet supported - so I2C1 peripheral is not defined
#endif
#endif
// Assume I2C1 for now - default I2C bus on Nucleo-F411RE and likely Nucleo-64 variants
I2C_TypeDef *s = I2C1;
#define I2C_IRQn I2C1_EV_IRQn
#define I2C_BUSFREQ 16
// Peripheral Input Clock speed in MHz.
// For STM32F446RE, the speed is 45MHz. Ideally, this should be determined
// at run-time from the APB1 clock, as it can vary from STM32 family to family.
// #define I2C_PERIPH_CLK 45
// I2C SR1 Status Register #1 bit definitions for convenience
// #define I2C_SR1_SMBALERT (1<<15) // SMBus alert
@ -80,52 +97,66 @@ I2C_TypeDef *s = I2C1;
// #define I2C_CR1_SMBUS (1<<1) // SMBus mode, 1=SMBus, 0=I2C
// #define I2C_CR1_PE (1<<0) // I2C Peripheral enable
// States of the STM32 I2C driver state machine
enum {TS_IDLE,TS_START,TS_W_ADDR,TS_W_DATA,TS_W_STOP,TS_R_ADDR,TS_R_DATA,TS_R_STOP};
/***************************************************************************
* Set I2C clock speed register. This should only be called outside of
* a transmission. The I2CManagerClass::_setClock() function ensures
* that it is only called at the beginning of an I2C transaction.
***************************************************************************/
void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) {
// Calculate a rise time appropriate to the requested bus speed
// Use 10x the rise time spec to enable integer divide of 62.5ns clock period
// Use 10x the rise time spec to enable integer divide of 50ns clock period
uint16_t t_rise;
uint32_t ccr_freq;
if (i2cClockSpeed < 200000L) {
// i2cClockSpeed = 100000L;
t_rise = 0x11; // (1000ns /62.5ns) + 1;
}
else if (i2cClockSpeed < 800000L)
while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further
// writes to CR1 while STOP is being executed!
// Disable the I2C device, as TRISE can only be programmed whilst disabled
s->CR1 &= ~(I2C_CR1_PE); // Disable I2C
s->CR1 |= I2C_CR1_SWRST; // reset the I2C
asm("nop"); // wait a bit... suggestion from online!
s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation
if (i2cClockSpeed > 100000UL)
{
i2cClockSpeed = 400000L;
t_rise = 0x06; // (300ns / 62.5ns) + 1;
// } else if (i2cClockSpeed < 1200000L) {
// i2cClockSpeed = 1000000L;
// t_rise = 120;
// if (i2cClockSpeed > 400000L)
// i2cClockSpeed = 400000L;
t_rise = 300; // nanoseconds
}
else
{
i2cClockSpeed = 100000L;
t_rise = 0x11; // (1000ns /62.5ns) + 1;
// i2cClockSpeed = 100000L;
t_rise = 1000; // nanoseconds
}
// Enable the I2C master mode
s->CR1 &= ~(I2C_CR1_PE); // Enable I2C
// Software reset the I2C peripheral
// s->CR1 |= I2C_CR1_SWRST; // reset the I2C
// Release reset
// s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation
// Calculate baudrate - using a rise time appropriate for the speed
ccr_freq = I2C_BUSFREQ * 1000000 / i2cClockSpeed / 2;
// Configure the rise time register - max allowed tRISE is 1000ns,
// so value = 1000ns * I2C_PERIPH_CLK MHz / 1000 + 1.
s->TRISE = (t_rise * i2c_MHz / 1000) + 1;
// Bit 15: I2C Master mode, 0=standard, 1=Fast Mode
// Bit 14: Duty, fast mode duty cycle
// Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns, so CCR divisor must be 0x50 (80 * 62.5ns = 5000ns)
s->CCR = (uint16_t)ccr_freq;
// Bit 14: Duty, fast mode duty cycle (use 2:1)
// Bit 11-0: FREQR
// if (i2cClockSpeed > 400000UL) {
// // In fast mode plus, I2C period is 3 * CCR * TPCLK1.
// // s->CCR &= ~(0x3000); // Clear all bits except 12 and 13 which must remain per reset value
// s->CCR = APB1clk1 / 3 / i2cClockSpeed; // Set I2C clockspeed to start!
// s->CCR |= 0xC000; // We need Fast Mode AND DUTY bits set
// } else {
// In standard and fast mode, I2C period is 2 * CCR * TPCLK1
s->CCR &= ~(0x3000); // Clear all bits except 12 and 13 which must remain per reset value
s->CCR |= (APB1clk1 / 2 / i2cClockSpeed); // Set I2C clockspeed to start!
// s->CCR |= (i2c_MHz * 500 / (i2cClockSpeed / 1000)); // Set I2C clockspeed to start!
// if (i2cClockSpeed > 100000UL)
// s->CCR |= 0xC000; // We need Fast Mode bits set as well
// }
// Configure the rise time register
s->TRISE = t_rise; // 1000 ns / 62.5 ns = 16 + 1
// DIAG(F("I2C_init() peripheral clock is now: %d, full reg is %x"), (s->CR2 & 0xFF), s->CR2);
// DIAG(F("I2C_init() peripheral CCR is now: %d"), s->CCR);
// DIAG(F("I2C_init() peripheral TRISE is now: %d"), s->TRISE);
// Enable the I2C master mode
s->CR1 |= I2C_CR1_PE; // Enable I2C
@ -136,32 +167,54 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) {
***************************************************************************/
void I2CManagerClass::I2C_init()
{
//Setting up the clocks
RCC->APB1ENR |= (1<<21); // Enable I2C CLOCK
RCC->AHB1ENR |= (1<<1); // Enable GPIOB CLOCK for PB8/PB9
// Query the clockspeed from the STM32 HAL layer
APB1clk1 = HAL_RCC_GetPCLK1Freq();
i2c_MHz = APB1clk1 / 1000000UL;
// DIAG(F("I2C_init() peripheral clock speed is: %d"), i2c_MHz);
// Enable clocks
RCC->APB1ENR |= RCC_APB1ENR_I2C1EN;//(1 << 21); // Enable I2C CLOCK
// Reset the I2C1 peripheral to initial state
RCC->APB1RSTR |= RCC_APB1RSTR_I2C1RST;
RCC->APB1RSTR &= ~RCC_APB1RSTR_I2C1RST;
// Standard I2C pins are SCL on PB8 and SDA on PB9
RCC->AHB1ENR |= (1<<1); // Enable GPIOB CLOCK for PB8/PB9
// Bits (17:16)= 1:0 --> Alternate Function for Pin PB8;
// Bits (19:18)= 1:0 --> Alternate Function for Pin PB9
GPIOB->MODER &= ~((3<<(8*2)) | (3<<(9*2))); // Clear all MODER bits for PB8 and PB9
GPIOB->MODER |= (2<<(8*2)) | (2<<(9*2)); // PB8 and PB9 set to ALT function
GPIOB->OTYPER |= (1<<8) | (1<<9); // PB8 and PB9 set to open drain output capability
GPIOB->OSPEEDR |= (3<<(8*2)) | (3<<(9*2)); // PB8 and PB9 set to High Speed mode
GPIOB->PUPDR &= ~((3<<(8*2)) | (3<<(9*2))); // Clear all PUPDR bits for PB8 and PB9
GPIOB->PUPDR |= (1<<(8*2)) | (1<<(9*2)); // PB8 and PB9 set to pull-up capability
// Alt Function High register routing pins PB8 and PB9 for I2C1:
// Bits (3:2:1:0) = 0:1:0:0 --> AF4 for pin PB8
// Bits (7:6:5:4) = 0:1:0:0 --> AF4 for pin PB9
GPIOB->AFR[1] &= ~((15<<0) | (15<<4)); // Clear all AFR bits for PB8 on low nibble, PB9 on next nibble up
GPIOB->AFR[1] |= (4<<0) | (4<<4); // PB8 on low nibble, PB9 on next nibble up
// Software reset the I2C peripheral
I2C1->CR1 &= ~I2C_CR1_PE; // Disable I2C1 peripheral
s->CR1 |= I2C_CR1_SWRST; // reset the I2C
asm("nop"); // wait a bit... suggestion from online!
s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation
// Program the peripheral input clock in CR2 Register in order to generate correct timings
s->CR2 |= I2C_BUSFREQ; // PCLK1 FREQUENCY in MHz
// Clear all bits in I2C CR2 register except reserved bits
s->CR2 &= 0xE000;
// Set I2C peripheral clock frequency
// s->CR2 |= I2C_PERIPH_CLK;
s->CR2 |= i2c_MHz;
// DIAG(F("I2C_init() peripheral clock is now: %d"), s->CR2);
// set own address to 00 - not used in master mode
I2C1->OAR1 = (1 << 14); // bit 14 should be kept at 1 according to the datasheet
#if defined(I2C_USE_INTERRUPTS)
// Setting NVIC
NVIC_SetPriority(I2C_IRQn, 1); // Match default priorities
NVIC_EnableIRQ(I2C_IRQn);
NVIC_SetPriority(I2C1_EV_IRQn, 1); // Match default priorities
NVIC_EnableIRQ(I2C1_EV_IRQn);
NVIC_SetPriority(I2C1_ER_IRQn, 1); // Match default priorities
NVIC_EnableIRQ(I2C1_ER_IRQn);
// CR2 Interrupt Settings
// Bit 15-13: reserved
@ -172,23 +225,28 @@ void I2CManagerClass::I2C_init()
// Bit 8: ITERREN - Error interrupt enable
// Bit 7-6: reserved
// Bit 5-0: FREQ - Peripheral clock frequency (max 50MHz)
// s->CR2 |= 0x0700; // Enable Buffer, Event and Error interrupts
s->CR2 |= 0x0300; // Enable Event and Error interrupts
s->CR2 |= (I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN); // Enable Buffer, Event and Error interrupts
#endif
// DIAG(F("I2C_init() setting initial I2C clock to 100KHz"));
// Calculate baudrate and set default rate for now
// Configure the Clock Control Register for 100KHz SCL frequency
// Bit 15: I2C Master mode, 0=standard, 1=Fast Mode
// Bit 14: Duty, fast mode duty cycle
// Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns, so CCR divisor must be 0x50 (80 * 62.5ns = 5000ns)
s->CCR = 0x0050;
// Bit 11-0: so CCR divisor would be clk / 2 / 100000 (where clk is in Hz)
// s->CCR = I2C_PERIPH_CLK * 5;
s->CCR &= ~(0x3000); // Clear all bits except 12 and 13 which must remain per reset value
s->CCR |= (APB1clk1 / 2 / 100000UL); // Set a default of 100KHz I2C clockspeed to start!
// Configure the rise time register - max allowed in 1000ns
s->TRISE = 0x0011; // 1000 ns / 62.5 ns = 16 + 1
// Configure the rise time register - max allowed is 1000ns, so value = 1000ns * I2C_PERIPH_CLK MHz / 1000 + 1.
s->TRISE = (1000 * i2c_MHz / 1000) + 1;
// DIAG(F("I2C_init() peripheral clock is now: %d, full reg is %x"), (s->CR2 & 0xFF), s->CR2);
// DIAG(F("I2C_init() peripheral CCR is now: %d"), s->CCR);
// DIAG(F("I2C_init() peripheral TRISE is now: %d"), s->TRISE);
// Enable the I2C master mode
s->CR1 |= I2C_CR1_PE; // Enable I2C
// Setting bus idle mode and wait for sync
}
/***************************************************************************
@ -198,42 +256,23 @@ void I2CManagerClass::I2C_sendStart() {
// Set counters here in case this is a retry.
rxCount = txCount = 0;
uint8_t temp;
// On a single-master I2C bus, the start bit won't be sent until the bus
// state goes to IDLE so we can request it without waiting. On a
// multi-master bus, the bus may be BUSY under control of another master,
// in which case we can avoid some arbitration failures by waiting until
// the bus state is IDLE. We don't do that here.
//while (s->SR2 & I2C_SR2_BUSY) {}
// If anything to send, initiate write. Otherwise initiate read.
if (operation == OPERATION_READ || ((operation == OPERATION_REQUEST) && !bytesToSend))
{
// Send start for read operation
s->CR1 |= I2C_CR1_ACK; // Enable the ACK
s->CR1 |= I2C_CR1_START; // Generate START
// Send address with read flag (1) or'd in
s->DR = (deviceAddress << 1) | 1; // send the address
while (!(s->SR1 && I2C_SR1_ADDR)); // wait for ADDR bit to set
// Special case for 1 byte reads!
if (bytesToReceive == 1)
{
s->CR1 &= ~I2C_CR1_ACK; // clear the ACK bit
temp = I2C1->SR1 | I2C1->SR2; // read SR1 and SR2 to clear the ADDR bit.... EV6 condition
s->CR1 |= I2C_CR1_STOP; // Stop I2C
}
else
temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit
}
else {
// Send start for write operation
s->CR1 |= I2C_CR1_ACK; // Enable the ACK
s->CR1 |= I2C_CR1_START; // Generate START
// Send address with write flag (0) or'd in
s->DR = (deviceAddress << 1) | 0; // send the address
while (!(s->SR1 && I2C_SR1_ADDR)); // wait for ADDR bit to set
temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit
}
// Check there's no STOP still in progress. If we OR the START bit into CR1
// and the STOP bit is already set, we could output multiple STOP conditions.
while (s->CR1 & I2C_CR1_STOP) {} // Wait for STOP bit to reset
s->CR2 |= (I2C_CR2_ITEVTEN | I2C_CR2_ITERREN); // Enable interrupts
s->CR2 &= ~I2C_CR2_ITBUFEN; // Don't enable buffer interupts yet.
s->CR1 &= ~I2C_CR1_POS; // Clear the POS bit
s->CR1 |= (I2C_CR1_ACK | I2C_CR1_START); // Enable the ACK and generate START
transactionState = TS_START;
}
/***************************************************************************
@ -252,9 +291,11 @@ void I2CManagerClass::I2C_close() {
s->CR1 &= ~I2C_CR1_PE; // Disable I2C peripheral
// Should never happen, but wait for up to 500us only.
unsigned long startTime = micros();
while ((s->CR1 && I2C_CR1_PE) != 0) {
if (micros() - startTime >= 500UL) break;
while ((s->CR1 & I2C_CR1_PE) != 0) {
if ((int32_t)(micros() - startTime) >= 500) break;
}
NVIC_DisableIRQ(I2C1_EV_IRQn);
NVIC_DisableIRQ(I2C1_ER_IRQn);
}
/***************************************************************************
@ -263,50 +304,217 @@ void I2CManagerClass::I2C_close() {
* (and therefore, indirectly, from I2CRB::wait() and I2CRB::isBusy()).
***************************************************************************/
void I2CManagerClass::I2C_handleInterrupt() {
volatile uint16_t temp_sr1, temp_sr2;
if (s->SR1 && I2C_SR1_ARLO) {
// Arbitration lost, restart
I2C_sendStart(); // Reinitiate request
} else if (s->SR1 && I2C_SR1_BERR) {
// Bus error
completionStatus = I2C_STATUS_BUS_ERROR;
state = I2C_STATE_COMPLETED;
} else if (s->SR1 && I2C_SR1_TXE) {
// Master write completed
if (s->SR1 && (1<<10)) {
// Nacked, send stop.
I2C_sendStop();
temp_sr1 = s->SR1;
// Check for errors first
if (temp_sr1 & (I2C_SR1_AF | I2C_SR1_ARLO | I2C_SR1_BERR)) {
// Check which error flag is set
if (temp_sr1 & I2C_SR1_AF)
{
s->SR1 &= ~(I2C_SR1_AF); // Clear AF
I2C_sendStop(); // Clear the bus
transactionState = TS_IDLE;
completionStatus = I2C_STATUS_NEGATIVE_ACKNOWLEDGE;
state = I2C_STATE_COMPLETED;
} else if (bytesToSend) {
// Acked, so send next byte
s->DR = sendBuffer[txCount++];
bytesToSend--;
} else if (bytesToReceive) {
// Last sent byte acked and no more to send. Send repeated start, address and read bit.
// s->I2CM.ADDR.bit.ADDR = (deviceAddress << 1) | 1;
} else {
// Check both TxE/BTF == 1 before generating stop
while (!(s->SR1 && I2C_SR1_TXE)); // Check TxE
while (!(s->SR1 && I2C_SR1_BTF)); // Check BTF
// No more data to send/receive. Initiate a STOP condition and finish
I2C_sendStop();
}
else if (temp_sr1 & I2C_SR1_ARLO)
{
// Arbitration lost, restart
s->SR1 &= ~(I2C_SR1_ARLO); // Clear ARLO
I2C_sendStart(); // Reinitiate request
transactionState = TS_START;
}
else if (temp_sr1 & I2C_SR1_BERR)
{
// Bus error
s->SR1 &= ~(I2C_SR1_BERR); // Clear BERR
I2C_sendStop(); // Clear the bus
transactionState = TS_IDLE;
completionStatus = I2C_STATUS_BUS_ERROR;
state = I2C_STATE_COMPLETED;
}
} else if (s->SR1 && I2C_SR1_RXNE) {
// Master read completed without errors
if (bytesToReceive == 1) {
// s->I2CM.CTRLB.bit.ACKACT = 1; // NAK final byte
I2C_sendStop(); // send stop
receiveBuffer[rxCount++] = s->DR; // Store received byte
bytesToReceive = 0;
}
else {
// No error flags, so process event according to current state.
switch (transactionState) {
case TS_START:
if (temp_sr1 & I2C_SR1_SB) {
// Event EV5
// Start bit has been sent successfully and we have the bus.
// If anything to send, initiate write. Otherwise initiate read.
if (operation == OPERATION_READ || ((operation == OPERATION_REQUEST) && !bytesToSend)) {
// Send address with read flag (1) or'd in
s->DR = (deviceAddress << 1) | 1; // send the address
transactionState = TS_R_ADDR;
} else {
// Send address with write flag (0) or'd in
s->DR = (deviceAddress << 1) | 0; // send the address
transactionState = TS_W_ADDR;
}
}
// SB bit is cleared by writing to DR (already done).
break;
case TS_W_ADDR:
if (temp_sr1 & I2C_SR1_ADDR) {
temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit
// Event EV6
// Address sent successfully, device has ack'd in response.
if (!bytesToSend) {
I2C_sendStop();
transactionState = TS_IDLE;
completionStatus = I2C_STATUS_OK;
state = I2C_STATE_COMPLETED;
} else if (bytesToReceive) {
// s->I2CM.CTRLB.bit.ACKACT = 0; // ACK all but final byte
} else {
// Put one byte into DR to load shift register.
s->DR = sendBuffer[txCount++];
bytesToSend--;
if (bytesToSend) {
// Put another byte to load DR
s->DR = sendBuffer[txCount++];
bytesToSend--;
}
if (!bytesToSend) {
// No more bytes to send.
// The TXE interrupt occurs when the DR is empty, and the BTF interrupt
// occurs when the shift register is also empty (one character later).
// To avoid repeated TXE interrupts during this time, we disable TXE interrupt.
s->CR2 &= ~I2C_CR2_ITBUFEN; // Wait for BTF interrupt, disable TXE interrupt
transactionState = TS_W_STOP;
} else {
// More data remaining to send after this interrupt, enable TXE interrupt.
s->CR2 |= I2C_CR2_ITBUFEN;
transactionState = TS_W_DATA;
}
}
}
break;
case TS_W_DATA:
if (temp_sr1 & I2C_SR1_TXE) {
// Event EV8_1/EV8
// Transmitter empty, write a byte to it.
if (bytesToSend) {
s->DR = sendBuffer[txCount++];
bytesToSend--;
if (!bytesToSend) {
s->CR2 &= ~I2C_CR2_ITBUFEN; // Disable TXE interrupt
transactionState = TS_W_STOP;
}
}
}
break;
case TS_W_STOP:
if (temp_sr1 & I2C_SR1_BTF) {
// Event EV8_2
// Done, last character sent. Anything to receive?
if (bytesToReceive) {
I2C_sendStart();
// NOTE: Three redundant BTF interrupts take place between the
// first BTF interrupt and the START interrupt. I've tried all sorts
// of ways to eliminate them, and the only thing that worked for
// me was to loop until the BTF bit becomes reset. Either way,
// it's a waste of processor time. Anyone got a solution?
//while (s->SR1 && I2C_SR1_BTF) {}
transactionState = TS_START;
} else {
I2C_sendStop();
transactionState = TS_IDLE;
completionStatus = I2C_STATUS_OK;
state = I2C_STATE_COMPLETED;
}
s->SR1 &= I2C_SR1_BTF; // Clear BTF interrupt
}
break;
case TS_R_ADDR:
if (temp_sr1 & I2C_SR1_ADDR) {
// Event EV6
// Address sent for receive.
// The next bit is different depending on whether there are
// 1 byte, 2 bytes or >2 bytes to be received, in accordance with the
// Programmers Reference RM0390.
if (bytesToReceive == 1) {
// Receive 1 byte
s->CR1 &= ~I2C_CR1_ACK; // Disable ack
temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit
// Next step will occur after a RXNE interrupt, so enable it
s->CR2 |= I2C_CR2_ITBUFEN;
transactionState = TS_R_STOP;
} else if (bytesToReceive == 2) {
// Receive 2 bytes
s->CR1 &= ~I2C_CR1_ACK; // Disable ACK for final byte
s->CR1 |= I2C_CR1_POS; // set POS flag to delay effect of ACK flag
// Next step will occur after a BTF interrupt, so disable RXNE interrupt
s->CR2 &= ~I2C_CR2_ITBUFEN;
temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit
transactionState = TS_R_STOP;
} else {
// >2 bytes, just wait for bytes to come in and ack them for the time being
// (ack flag has already been set).
// Next step will occur after a BTF interrupt, so disable RXNE interrupt
s->CR2 &= ~I2C_CR2_ITBUFEN;
temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit
transactionState = TS_R_DATA;
}
}
break;
case TS_R_DATA:
// Event EV7/EV7_1
if (temp_sr1 & I2C_SR1_BTF) {
// Byte received in receiver - read next byte
if (bytesToReceive == 3) {
// Getting close to the last byte, so a specific sequence is recommended.
s->CR1 &= ~I2C_CR1_ACK; // Reset ack for next byte received.
transactionState = TS_R_STOP;
}
receiveBuffer[rxCount++] = s->DR; // Store received byte
bytesToReceive--;
}
break;
case TS_R_STOP:
if (temp_sr1 & I2C_SR1_BTF) {
// Event EV7 (last one)
// When we've got here, the receiver has got the last two bytes
// (or one byte, if only one byte is being received),
// and NAK has already been sent, so we need to read from the receiver.
if (bytesToReceive) {
if (bytesToReceive > 1)
I2C_sendStop();
while(bytesToReceive) {
receiveBuffer[rxCount++] = s->DR; // Store received byte(s)
bytesToReceive--;
}
// Finish.
transactionState = TS_IDLE;
completionStatus = I2C_STATUS_OK;
state = I2C_STATE_COMPLETED;
}
} else if (temp_sr1 & I2C_SR1_RXNE) {
if (bytesToReceive == 1) {
// One byte on a single-byte transfer. Ack has already been set.
I2C_sendStop();
receiveBuffer[rxCount++] = s->DR; // Store received byte
bytesToReceive--;
// Finish.
transactionState = TS_IDLE;
completionStatus = I2C_STATUS_OK;
state = I2C_STATE_COMPLETED;
} else
s->SR1 &= I2C_SR1_RXNE; // Acknowledge interrupt
}
break;
}
// If we've received an interrupt at any other time, we're not interested so clear it
// to prevent it recurring ad infinitum.
s->SR1 = 0;
}
}
#endif /* I2CMANAGER_STM32_H */

View File

@ -176,6 +176,13 @@ bool IODevice::exists(VPIN vpin) {
return findDevice(vpin) != NULL;
}
// Return the status of the device att vpin.
uint8_t IODevice::getStatus(VPIN vpin) {
IODevice *dev = findDevice(vpin);
if (!dev) return false;
return dev->_deviceState;
}
// check whether the pin supports notification. If so, then regular _read calls are not required.
bool IODevice::hasCallback(VPIN vpin) {
IODevice *dev = findDevice(vpin);

View File

@ -27,17 +27,6 @@
// Define symbol DIAG_LOOPTIMES to enable CS loop execution time to be reported
//#define DIAG_LOOPTIMES
// Define symbol IO_NO_HAL to reduce FLASH footprint when HAL features not required
// The HAL is disabled by default on Nano and Uno platforms, because of limited flash space.
#include "defines.h"
#if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO)
#if defined(DISABLE_DIAG) && defined(DISABLE_EEPROM) && defined(DISABLE_PROG)
#warning you have sacrificed DIAG for HAL
#else
#define IO_NO_HAL
#endif
#endif
// Define symbol IO_SWITCH_OFF_SERVO to set the PCA9685 output to 0 when an
// animation has completed. This switches off the servo motor, preventing
// the continuous buzz sometimes found on servos, and reducing the
@ -165,6 +154,9 @@ public:
// exists checks whether there is a device owning the specified vpin
static bool exists(VPIN vpin);
// getStatus returns the state of the device at the specified vpin
static uint8_t getStatus(VPIN vpin);
// Enable shared interrupt on specified pin for GPIO extender modules. The extender module
// should pull down this pin when requesting a scan. The pin may be shared by multiple modules.
// Without the shared interrupt, input states are scanned periodically to detect changes on
@ -388,6 +380,7 @@ private:
uint8_t *_pinInUse;
};
#ifndef IO_NO_HAL
/////////////////////////////////////////////////////////////////////////////////////////////////////
/*
* IODevice subclass for EX-Turntable.
@ -416,10 +409,14 @@ private:
void _begin() override;
void _loop(unsigned long currentMicros) override;
int _read(VPIN vpin) override;
void _broadcastStatus (VPIN vpin, uint8_t status, uint8_t activity);
void _writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_t duration) override;
void _display() override;
uint8_t _stepperStatus;
uint8_t _previousStatus;
uint8_t _currentActivity;
};
#endif
/////////////////////////////////////////////////////////////////////////////////////////////////////

View File

@ -20,20 +20,21 @@
/*
* The IO_EXTurntable device driver is used to control a turntable via an Arduino with a stepper motor over I2C.
*
* The EX-Turntable code lives in a separate repo (https://github.com/DCC-EX/Turntable-EX) and contains the stepper motor logic.
* The EX-Turntable code lives in a separate repo (https://github.com/DCC-EX/EX-Turntable) and contains the stepper motor logic.
*
* This device driver sends a step position to Turntable-EX to indicate the step position to move to using either of these commands:
* This device driver sends a step position to EX-Turntable to indicate the step position to move to using either of these commands:
* <D TT vpin steps activity> in the serial console
* MOVETT(vpin, steps, activity) in EX-RAIL
* Refer to the documentation for further information including the valid activities.
*/
#ifndef IO_EXTurntable_h
#define IO_EXTurntable_h
#include "IODevice.h"
#include "I2CManager.h"
#include "DIAG.h"
#include "Turntables.h"
#include "CommandDistributor.h"
#ifndef IO_NO_HAL
void EXTurntable::create(VPIN firstVpin, int nPins, I2CAddress I2CAddress) {
new EXTurntable(firstVpin, nPins, I2CAddress);
@ -44,6 +45,8 @@ EXTurntable::EXTurntable(VPIN firstVpin, int nPins, I2CAddress I2CAddress) {
_firstVpin = firstVpin;
_nPins = nPins;
_I2CAddress = I2CAddress;
_stepperStatus = 0;
_previousStatus = 0;
addDevice(this);
}
@ -51,6 +54,7 @@ EXTurntable::EXTurntable(VPIN firstVpin, int nPins, I2CAddress I2CAddress) {
void EXTurntable::_begin() {
I2CManager.begin();
if (I2CManager.exists(_I2CAddress)) {
DIAG(F("EX-Turntable device found, I2C:%s"), _I2CAddress.toString());
#ifdef DIAG_IO
_display();
#endif
@ -67,15 +71,19 @@ void EXTurntable::_loop(unsigned long currentMicros) {
uint8_t readBuffer[1];
I2CManager.read(_I2CAddress, readBuffer, 1);
_stepperStatus = readBuffer[0];
// DIAG(F("Turntable-EX returned status: %d"), _stepperStatus);
delayUntil(currentMicros + 500000); // Wait 500ms before checking again, turntables turn slowly
if (_stepperStatus != _previousStatus && _stepperStatus == 0) { // Broadcast when a rotation finishes
if ( _currentActivity < 4) {
_broadcastStatus(_firstVpin, _stepperStatus, _currentActivity);
}
_previousStatus = _stepperStatus;
}
delayUntil(currentMicros + 100000); // Wait 100ms before checking again
}
// Read returns status as obtained in our loop.
// Return false if our status value is invalid.
int EXTurntable::_read(VPIN vpin) {
if (_deviceState == DEVSTATE_FAILED) return 0;
// DIAG(F("_read status: %d"), _stepperStatus);
if (_stepperStatus > 1) {
return false;
} else {
@ -83,6 +91,17 @@ int EXTurntable::_read(VPIN vpin) {
}
}
// If a status change has occurred for a turntable object, broadcast it
void EXTurntable::_broadcastStatus (VPIN vpin, uint8_t status, uint8_t activity) {
Turntable *tto = Turntable::getByVpin(vpin);
if (tto) {
if (activity < 4) {
tto->setMoving(status);
CommandDistributor::broadcastTurntable(tto->getId(), tto->getPosition(), status);
}
}
}
// writeAnalogue to send the steps and activity to Turntable-EX.
// Sends 3 bytes containing the MSB and LSB of the step count, and activity.
// value contains the steps, bit shifted to MSB + LSB.
@ -100,6 +119,7 @@ int EXTurntable::_read(VPIN vpin) {
// Acc_Off = 9 // Turn accessory pin off
void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_t duration) {
if (_deviceState == DEVSTATE_FAILED) return;
if (value < 0) return;
uint8_t stepsMSB = value >> 8;
uint8_t stepsLSB = value & 0xFF;
#ifdef DIAG_IO
@ -108,7 +128,10 @@ void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_
DIAG(F("I2CManager write I2C Address:%d stepsMSB:%d stepsLSB:%d activity:%d"),
_I2CAddress.toString(), stepsMSB, stepsLSB, activity);
#endif
_stepperStatus = 1; // Tell the device driver Turntable-EX is busy
if (activity < 4) _stepperStatus = 1; // Tell the device driver Turntable-EX is busy
_previousStatus = _stepperStatus;
_currentActivity = activity;
_broadcastStatus(vpin, _stepperStatus, activity); // Broadcast when the rotation starts
I2CManager.write(_I2CAddress, 3, stepsMSB, stepsLSB, activity);
}

View File

@ -34,16 +34,15 @@ public:
if (checkNoOverlap(vpin, nPins, i2cAddress)) new PCA9555(vpin,nPins, i2cAddress, interruptPin);
}
private:
// Constructor
PCA9555(VPIN vpin, int nPins, uint8_t I2CAddress, int interruptPin=-1)
PCA9555(VPIN vpin, uint8_t nPins, I2CAddress I2CAddress, int interruptPin=-1)
: GPIOBase<uint16_t>((FSH *)F("PCA9555"), vpin, nPins, I2CAddress, interruptPin)
{
requestBlock.setRequestParams(_I2CAddress, inputBuffer, sizeof(inputBuffer),
outputBuffer, sizeof(outputBuffer));
outputBuffer[0] = REG_INPUT_P0;
}
private:
void _writeGpioPort() override {
I2CManager.write(_I2CAddress, 3, REG_OUTPUT_P0, _portOutputState, _portOutputState>>8);
}

View File

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

View File

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

View File

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

View File

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

268
Turntables.cpp Normal file
View File

@ -0,0 +1,268 @@
/*
* © 2023 Peter Cole
* All rights reserved.
*
* This file is part of CommandStation-EX
*
* This is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* It is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/
#include "defines.h"
#include <Arduino.h>
#include "Turntables.h"
#include "StringFormatter.h"
#include "CommandDistributor.h"
#include "EXRAIL2.h"
#include "DCC.h"
// No turntable support without HAL
#ifndef IO_NO_HAL
/*
* Protected static data
*/
Turntable *Turntable::_firstTurntable = 0;
/*
* Public static data
*/
int Turntable::turntablelistHash = 0;
/*
* Protected static functions
*/
// Add new turntable to end of list
void Turntable::add(Turntable *tto) {
if (!_firstTurntable) {
_firstTurntable = tto;
} else {
Turntable *ptr = _firstTurntable;
for ( ; ptr->_nextTurntable!=0; ptr=ptr->_nextTurntable) {}
ptr->_nextTurntable = tto;
}
turntablelistHash++;
}
// Add a position
void Turntable::addPosition(uint8_t idx, uint16_t value, uint16_t angle) {
_turntablePositions.insert(idx, value, angle);
}
// Get value for position
uint16_t Turntable::getPositionValue(uint8_t position) {
TurntablePosition* currentPosition = _turntablePositions.getHead();
while (currentPosition) {
if (currentPosition->index == position) {
return currentPosition->data;
}
currentPosition = currentPosition->next;
}
return false;
}
// Get value for position
uint16_t Turntable::getPositionAngle(uint8_t position) {
TurntablePosition* currentPosition = _turntablePositions.getHead();
while (currentPosition) {
if (currentPosition->index == position) {
return currentPosition->angle;
}
currentPosition = currentPosition->next;
}
return false;
}
// Get the count of positions associated with the turntable
uint8_t Turntable::getPositionCount() {
TurntablePosition* currentPosition = _turntablePositions.getHead();
uint8_t count = 0;
while (currentPosition) {
count++;
currentPosition = currentPosition->next;
}
return count;
}
/*
* Public static functions
*/
// Find turntable from list
Turntable *Turntable::get(uint16_t id) {
for (Turntable *tto = _firstTurntable; tto != nullptr; tto = tto->_nextTurntable)
if (tto->_turntableData.id == id) return tto;
return NULL;
}
// Find turntable via Vpin
Turntable *Turntable::getByVpin(VPIN vpin) {
for (Turntable *tto = _firstTurntable; tto != nullptr; tto = tto->_nextTurntable) {
if (tto->isEXTT()) {
EXTTTurntable *exttTto = static_cast<EXTTTurntable*>(tto);
if (exttTto->getVpin() == vpin) {
return tto;
}
}
}
return nullptr;
}
// Get the current position for turntable with the specified ID
uint8_t Turntable::getPosition(uint16_t id) {
Turntable *tto = get(id);
if (!tto) return false;
return tto->getPosition();
}
// Got the moving state of the specified turntable
bool Turntable::ttMoving(uint16_t id) {
Turntable *tto = get(id);
if (!tto) return false;
return tto->isMoving();
}
// Initiate a turntable move
bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) {
#if defined(DIAG_IO)
DIAG(F("Rotate turntable %d to position %d, activity %d)"), id, position, activity);
#endif
Turntable *tto = Turntable::get(id);
if (!tto) return false;
if (tto->isMoving()) return false;
bool ok = tto->setPositionInternal(position, activity);
if (ok) {
// We only deal with broadcasts for DCC turntables here, EXTT in the device driver
if (!tto->isEXTT()) {
CommandDistributor::broadcastTurntable(id, position, false);
}
// Trigger EXRAIL rotateEvent for both types here if changed
#if defined(EXRAIL_ACTIVE)
bool rotated = false;
if (position != tto->_previousPosition) rotated = true;
RMFT2::rotateEvent(id, rotated);
#endif
}
return ok;
}
/*************************************************************************************
* EXTTTurntable - EX-Turntable device.
*
*************************************************************************************/
// Private constructor
EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin) :
Turntable(id, TURNTABLE_EXTT)
{
_exttTurntableData.vpin = vpin;
}
using DevState = IODevice::DeviceStateEnum;
// Create function
Turntable *EXTTTurntable::create(uint16_t id, VPIN vpin) {
#ifndef IO_NO_HAL
Turntable *tto = get(id);
if (tto) {
if (tto->isType(TURNTABLE_EXTT)) {
EXTTTurntable *extt = (EXTTTurntable *)tto;
extt->_exttTurntableData.vpin = vpin;
return tto;
}
}
if (!IODevice::exists(vpin)) return nullptr;
if (IODevice::getStatus(vpin) == DevState::DEVSTATE_FAILED) return nullptr;
if (Turntable::getByVpin(vpin)) return nullptr;
tto = (Turntable *)new EXTTTurntable(id, vpin);
DIAG(F("Turntable 0x%x size %d size %d"), tto, sizeof(Turntable), sizeof(struct TurntableData));
return tto;
#else
(void)id;
(void)vpin;
return NULL;
#endif
}
void EXTTTurntable::print(Print *stream) {
StringFormatter::send(stream, F("<i %d EXTURNTABLE %d>\n"), _turntableData.id, _exttTurntableData.vpin);
}
// EX-Turntable specific code for moving to the specified position
bool EXTTTurntable::setPositionInternal(uint8_t position, uint8_t activity) {
#ifndef IO_NO_HAL
int16_t value;
if (position == 0) {
value = 0; // Position 0 is just to send activities
} else {
if (activity > 1) return false; // If sending a position update, only phase changes valid (0|1)
value = getPositionValue(position); // Get position value from position list
}
if (position > 0 && !value) return false; // Return false if it's not a valid position
// Set position via device driver
_previousPosition = _turntableData.position;
_turntableData.position = position;
EXTurntable::writeAnalogue(_exttTurntableData.vpin, value, activity);
#else
(void)position;
#endif
return true;
}
/*************************************************************************************
* DCCTurntable - DCC Turntable device.
*
*************************************************************************************/
// Private constructor
DCCTurntable::DCCTurntable(uint16_t id) : Turntable(id, TURNTABLE_DCC) {}
// Create function
Turntable *DCCTurntable::create(uint16_t id) {
#ifndef IO_NO_HAL
Turntable *tto = get(id);
if (!tto) {
tto = (Turntable *)new DCCTurntable(id);
DIAG(F("Turntable 0x%x size %d size %d"), tto, sizeof(Turntable), sizeof(struct TurntableData));
}
return tto;
#else
(void)id;
return NULL;
#endif
}
void DCCTurntable::print(Print *stream) {
StringFormatter::send(stream, F("<i %d DCCTURNTABLE>\n"), _turntableData.id);
}
// EX-Turntable specific code for moving to the specified position
bool DCCTurntable::setPositionInternal(uint8_t position, uint8_t activity) {
#ifndef IO_NO_HAL
int16_t value = getPositionValue(position);
if (position == 0 || !value) return false; // Return false if it's not a valid position
// Set position via device driver
int16_t addr=value>>3;
int16_t subaddr=(value>>1) & 0x03;
bool active=value & 0x01;
_previousPosition = _turntableData.position;
_turntableData.position = position;
DCC::setAccessory(addr, subaddr, active);
#else
(void)position;
#endif
return true;
}
#endif

243
Turntables.h Normal file
View File

@ -0,0 +1,243 @@
/*
* © 2023 Peter Cole
* All rights reserved.
*
* This file is part of CommandStation-EX
*
* This is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* It is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/
#ifndef TURNTABLES_H
#define TURNTABLES_H
#include <Arduino.h>
#include "IODevice.h"
#include "StringFormatter.h"
// No turntable support without HAL
#ifndef IO_NO_HAL
// Turntable type definitions
// EXTT = EX-Turntable
// DCC = DCC accessory turntables - to be added later
enum {
TURNTABLE_EXTT = 0,
TURNTABLE_DCC = 1,
};
/*************************************************************************************
* Turntable positions.
*
*************************************************************************************/
struct TurntablePosition {
uint8_t index;
uint16_t data;
uint16_t angle;
TurntablePosition* next;
TurntablePosition(uint8_t idx, uint16_t value, uint16_t angle) : index(idx), data(value), angle(angle), next(nullptr) {}
};
class TurntablePositionList {
public:
TurntablePositionList() : head(nullptr) {}
void insert(uint8_t idx, uint16_t value, uint16_t angle) {
TurntablePosition* newPosition = new TurntablePosition(idx, value, angle);
if(!head) {
head = newPosition;
} else {
newPosition->next = head;
head = newPosition;
}
}
TurntablePosition* getHead() {
return head;
}
private:
TurntablePosition* head;
};
/*************************************************************************************
* Turntable - Base class for turntables.
*
*************************************************************************************/
class Turntable {
protected:
/*
* Object data
*/
// Data common to all turntable types
struct TurntableData {
union {
struct {
bool hidden : 1;
bool turntableType : 1;
uint8_t position : 6; // Allows up to 63 positions including 0/home
};
uint8_t flags;
};
uint16_t id;
} _turntableData;
// Pointer to next turntable object
Turntable *_nextTurntable = 0;
// Linked list for positions
TurntablePositionList _turntablePositions;
// Store the previous position to allow checking for changes
uint8_t _previousPosition = 0;
// Store the current state of the turntable
bool _isMoving = false;
/*
* Constructor
*/
Turntable(uint16_t id, uint8_t turntableType) {
_turntableData.id = id;
_turntableData.turntableType = turntableType;
_turntableData.hidden = false;
_turntableData.position = 0;
add(this);
}
/*
* Static data
*/
static Turntable *_firstTurntable;
static int _turntablelistHash;
/*
* Virtual functions
*/
virtual bool setPositionInternal(uint8_t position, uint8_t activity) = 0;
/*
* Static functions
*/
static void add(Turntable *tto);
public:
static Turntable *get(uint16_t id);
static Turntable *getByVpin(VPIN vpin);
/*
* Static data
*/
static int turntablelistHash;
/*
* Public base class functions
*/
inline uint8_t getPosition() { return _turntableData.position; }
inline bool isHidden() { return _turntableData.hidden; }
inline void setHidden(bool h) {_turntableData.hidden=h; }
inline bool isType(uint8_t type) { return _turntableData.turntableType == type; }
inline bool isEXTT() const { return _turntableData.turntableType == TURNTABLE_EXTT; }
inline uint16_t getId() { return _turntableData.id; }
inline Turntable *next() { return _nextTurntable; }
void printState(Print *stream);
void addPosition(uint8_t idx, uint16_t value, uint16_t angle);
uint16_t getPositionValue(uint8_t position);
uint16_t getPositionAngle(uint8_t position);
uint8_t getPositionCount();
bool isMoving() { return _isMoving; }
void setMoving(bool moving) { _isMoving=moving; }
/*
* Virtual functions
*/
virtual void print(Print *stream) {
(void)stream; // suppress compiler warnings
}
virtual ~Turntable() {} // Destructor
/*
* Public static functions
*/
inline static bool exists(uint16_t id) { return get(id) != 0; }
static bool setPosition(uint16_t id, uint8_t position, uint8_t activity=0);
static uint8_t getPosition(uint16_t id);
static bool ttMoving(uint16_t id);
inline static Turntable *first() { return _firstTurntable; }
static bool printAll(Print *stream) {
bool gotOne = false;
for (Turntable *tto = _firstTurntable; tto != 0; tto = tto->_nextTurntable)
if (!tto->isHidden()) {
gotOne = true;
StringFormatter::send(stream, F("<I %d %d>\n"), tto->getId(), tto->getPosition());
}
return gotOne;
}
};
/*************************************************************************************
* EXTTTurntable - EX-Turntable device.
*
*************************************************************************************/
class EXTTTurntable : public Turntable {
private:
// EXTTTurntableData contains device specific data
struct EXTTTurntableData {
VPIN vpin;
} _exttTurntableData;
// Constructor
EXTTTurntable(uint16_t id, VPIN vpin);
public:
// Create function
static Turntable *create(uint16_t id, VPIN vpin);
void print(Print *stream) override;
VPIN getVpin() const { return _exttTurntableData.vpin; }
protected:
// EX-Turntable specific code for setting position
bool setPositionInternal(uint8_t position, uint8_t activity) override;
};
/*************************************************************************************
* DCCTurntable - DCC accessory Turntable device.
*
*************************************************************************************/
class DCCTurntable : public Turntable {
private:
// Constructor
DCCTurntable(uint16_t id);
public:
// Create function
static Turntable *create(uint16_t id);
void print(Print *stream) override;
protected:
// DCC specific code for setting position
bool setPositionInternal(uint8_t position, uint8_t activity=0) override;
};
#endif
#endif

View File

@ -144,9 +144,9 @@
#define DISABLE_EEPROM
#endif
// STM32 support for native I2C is awaiting development
#ifndef I2C_USE_WIRE
#define I2C_USE_WIRE
#endif
// #ifndef I2C_USE_WIRE
// #define I2C_USE_WIRE
// #endif
/* TODO when ready
#elif defined(ARDUINO_ARCH_RP2040)
@ -213,6 +213,19 @@
//
#define WIFI_SERIAL_LINK_SPEED 115200
////////////////////////////////////////////////////////////////////////////////
//
// Define symbol IO_NO_HAL to reduce FLASH footprint when HAL features not required
// The HAL is disabled by default on Nano and Uno platforms, because of limited flash space.
//
#if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO)
#if defined(DISABLE_DIAG) && defined(DISABLE_EEPROM) && defined(DISABLE_PROG)
#warning you have sacrificed DIAG for HAL
#else
#define IO_NO_HAL
#endif
#endif
#if __has_include ( "myAutomation.h")
#if defined(HAS_ENOUGH_MEMORY) || defined(DISABLE_EEPROM) || defined(DISABLE_PROG)
#define EXRAIL_ACTIVE

View File

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

View File

@ -30,8 +30,7 @@ include_dir = .
[env]
build_flags = -Wall -Wextra
monitor_filters = time
; lib_deps = adafruit/Adafruit ST7735 and ST7789 Library @ ^1.10.0
; monitor_filters = time
[env:samd21-dev-usb]
platform = atmelsam
@ -60,7 +59,7 @@ framework = arduino
lib_deps = ${env.lib_deps}
monitor_speed = 115200
monitor_echo = yes
build_flags = -std=c++17 ; -DI2C_USE_WIRE -DDIAG_LOOPTIMES -DDIAG_IO
build_flags = -std=c++17
[env:mega2560-debug]
platform = atmelavr
@ -108,7 +107,7 @@ lib_deps =
SPI
monitor_speed = 115200
monitor_echo = yes
build_flags = ; -DDIAG_LOOPTIMES
build_flags =
[env:mega328]
platform = atmelavr
@ -190,10 +189,75 @@ platform = ststm32
board = nucleo_f446re
framework = arduino
lib_deps = ${env.lib_deps}
build_flags = -std=c++17 -Os -g2 -Wunused-variable ; -DDIAG_LOOPTIMES ; -DDIAG_IO
build_flags = -std=c++17 -Os -g2 -Wunused-variable
monitor_speed = 115200
monitor_echo = yes
; Experimental - no reason this should not work, but not
; tested as yet
;
[env:Nucleo-F401RE]
platform = ststm32
board = nucleo_f401re
framework = arduino
lib_deps = ${env.lib_deps}
build_flags = -std=c++17 -Os -g2 -Wunused-variable
monitor_speed = 115200
monitor_echo = yes
; Commented out by default as the F13ZH has variant files
; but NOT the nucleo_f413zh.json file which needs to be
; installed before you can let PlatformIO see this
;
; [env:Nucleo-F413ZH]
; platform = ststm32
; board = nucleo_f413zh
; framework = arduino
; lib_deps = ${env.lib_deps}
; build_flags = -std=c++17 -Os -g2 -Wunused-variable
; monitor_speed = 115200
; monitor_echo = yes
; Commented out by default as the F446ZE needs variant files
; installed before you can let PlatformIO see this
;
; [env:Nucleo-F446ZE]
; platform = ststm32
; board = nucleo_f446ze
; framework = arduino
; lib_deps = ${env.lib_deps}
; build_flags = -std=c++17 -Os -g2 -Wunused-variable
; monitor_speed = 115200
; monitor_echo = yes
; Commented out by default as the F412ZG needs variant files
; installed before you can let PlatformIO see this
;
; [env:Nucleo-F412ZG]
; platform = ststm32
; board = blah_f412zg
; framework = arduino
; lib_deps = ${env.lib_deps}
; build_flags = -std=c++17 -Os -g2 -Wunused-variable
; monitor_speed = 115200
; monitor_echo = yes
; upload_protocol = stlink
; Experimental - Ethernet work still in progress
;
; [env:Nucleo-F429ZI]
; platform = ststm32
; board = nucleo_f429zi
; framework = arduino
; lib_deps = ${env.lib_deps}
; arduino-libraries/Ethernet @ ^2.0.1
; stm32duino/STM32Ethernet @ ^1.3.0
; stm32duino/STM32duino LwIP @ ^2.1.2
; build_flags = -std=c++17 -Os -g2 -Wunused-variable
; monitor_speed = 115200
; monitor_echo = yes
; upload_protocol = stlink
[env:Teensy3_2]
platform = teensy
board = teensy31
@ -233,4 +297,3 @@ framework = arduino
build_flags = -std=c++17 -Os -g2
lib_deps = ${env.lib_deps}
lib_ignore =

View File

@ -3,7 +3,33 @@
#include "StringFormatter.h"
#define VERSION "5.1.5LCC"
#define VERSION "5.1.14"
// 5.1.14 - Fixed IFTTPOSITION
// 5.1.13 - Changed turntable broadcast from i to I due to server string conflict
// 5.1.12 - Added Power commands <0 A> & <1 A> etc. and update to <=>
// Added EXRAIL SET_POWER(track, ON/OFF)
// Fixed a problem whereby <1 MAIN> also powered on PROG track
// Added functions to TrackManager.cpp to allow UserAddin code for power display on OLED/LCD
// Added - returnMode(byte t), returnDCAddr(byte t) & getModeName(byte Mode)
// 5.1.11 - STM32F4xx revised I2C clock setup, no correctly sets clock and has fully variable frequency selection
// 5.1.10 - STM32F4xx DCCEXanalogWrite to handle PWM generation for TrackManager DC/DCX
// - STM32F4xx DCC 58uS timer now using non-PWM output timers where possible
// - ESP32 brakeCanPWM check now detects UNUSED_PIN
// - ARM architecture brakeCanPWM now uses digitalPinHasPWM()
// - STM32F4xx shadowpin extensions to handle pins on ports D, E and F
// 5.1.9 - Fixed IO_PCA9555'h to work with PCA9548 mux, tested OK
// 5.1.8 - STM32Fxx ADCee extension to support ADCs #2 and #3
// 5.1.7 - Fix turntable broadcasts for non-movement activities and <JP> result
// 5.1.6 - STM32F4xx native I2C driver added
// 5.1.5 - Added turntable object and EXRAIL commands
// - <I ...>, <JO ...>, <JP ...> - turntable commands
// - DCC_TURNTABLE, EXTT_TURNTABLE, IFTTPOSITION, ONROTATE, ROTATE, ROTATE_DCC, TT_ADDPOSITION, WAITFORTT EXRAIL
// 5.1.4 - Added ONOVERLOAD & AFTEROVERLOAD to EXRAIL
// 5.1.3 - Make parser more fool proof
// 5.1.2 - Bugfix: ESP32 30ms off time
// 5.1.1 - Check bad AT firmware version
// - Update IO_PCA9555.h reflecting IO_MCP23017.h changes to support PCA9548 mux
// 5.0.1 - Bugfix: execute 30ms off time before rejoin
// 5.0.0 - Make 4.2.69 the 5.0.0 release
// 4.2.69 - Bugfix: Make <!> work in DC mode
// 4.2.68 - Rename track mode OFF to NONE