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

Compare commits

..

No commits in common. "a021895758ec84df0db964ff1bbad865e0c5e798" and "e9f534be6a9de077e9d86911f8e95669ff1cb4ba" have entirely different histories.

30 changed files with 382 additions and 2020 deletions

2
.gitignore vendored
View File

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

View File

@ -161,10 +161,6 @@ void CommandDistributor::broadcastTurnout(int16_t id, bool isClosed ) {
#endif #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) { void CommandDistributor::broadcastClockTime(int16_t time, int8_t rate) {
// The JMRI clock command is of the form : PFT65871<;>4 // The JMRI clock command is of the form : PFT65871<;>4
// The CS broadcast is of the form "<jC mmmm nn" where mmmm is time minutes and dd speed // The CS broadcast is of the form "<jC mmmm nn" where mmmm is time minutes and dd speed
@ -269,6 +265,6 @@ void CommandDistributor::broadcastRaw(clientType type, char * msg) {
broadcastReply(type, F("%s"),msg); broadcastReply(type, F("%s"),msg);
} }
void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr) { void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr) {
broadcastReply(COMMAND_TYPE, format,trackLetter, dcAddr); broadcastReply(COMMAND_TYPE, format,trackLetter,dcAddr);
} }

View File

@ -49,13 +49,12 @@ public :
static void broadcastLoco(byte slot); static void broadcastLoco(byte slot);
static void broadcastSensor(int16_t id, bool value); static void broadcastSensor(int16_t id, bool value);
static void broadcastTurnout(int16_t id, bool isClosed); 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 broadcastClockTime(int16_t time, int8_t rate);
static void setClockTime(int16_t time, int8_t rate, byte opt); static void setClockTime(int16_t time, int8_t rate, byte opt);
static int16_t retClockTime(); static int16_t retClockTime();
static void broadcastPower(); static void broadcastPower();
static void broadcastRaw(clientType type,char * msg); static void broadcastRaw(clientType type,char * msg);
static void broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr); static void broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr);
template<typename... Targs> static void broadcastReply(clientType type, Targs... msg); template<typename... Targs> static void broadcastReply(clientType type, Targs... msg);
static void forget(byte clientId); static void forget(byte clientId);

View File

@ -60,8 +60,8 @@ Once a new OPCODE is decided upon, update this list.
G, G,
h, h,
H, Turnout state broadcast H, Turnout state broadcast
i, Server details string i, Reserved for future use - Turntable object broadcast
I, Turntable object command, control, and broadcast I, Reserved for future use - Turntable object command and control
j, Throttle responses j, Throttle responses
J, Throttle queries J, Throttle queries
k, Reserved for future use - Potentially Railcom k, Reserved for future use - Potentially Railcom
@ -114,7 +114,6 @@ Once a new OPCODE is decided upon, update this list.
#include "TrackManager.h" #include "TrackManager.h"
#include "DCCTimer.h" #include "DCCTimer.h"
#include "EXRAIL2.h" #include "EXRAIL2.h"
#include "Turntables.h"
// This macro can't be created easily as a portable function because the // This macro can't be created easily as a portable function because the
// flashlist requires a far pointer for high flash access. // flashlist requires a far pointer for high flash access.
@ -122,7 +121,7 @@ Once a new OPCODE is decided upon, update this list.
for (int16_t i=0;;i+=sizeof(flashList[0])) { \ for (int16_t i=0;;i+=sizeof(flashList[0])) { \
int16_t value=GETHIGHFLASHW(flashList,i); \ int16_t value=GETHIGHFLASHW(flashList,i); \
if (value==INT16_MAX) break; \ if (value==INT16_MAX) break; \
StringFormatter::send(stream,F(" %d"),value); \ if (value != 0) StringFormatter::send(stream,F(" %d"),value); \
} }
@ -157,10 +156,7 @@ const int16_t HASH_KEYWORD_VPIN=-415;
const int16_t HASH_KEYWORD_A='A'; const int16_t HASH_KEYWORD_A='A';
const int16_t HASH_KEYWORD_C='C'; const int16_t HASH_KEYWORD_C='C';
const int16_t HASH_KEYWORD_G='G'; const int16_t HASH_KEYWORD_G='G';
const int16_t HASH_KEYWORD_H='H';
const int16_t HASH_KEYWORD_I='I'; 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_R='R';
const int16_t HASH_KEYWORD_T='T'; const int16_t HASH_KEYWORD_T='T';
const int16_t HASH_KEYWORD_X='X'; const int16_t HASH_KEYWORD_X='X';
@ -172,8 +168,6 @@ const int16_t HASH_KEYWORD_ANOUT = -26399;
const int16_t HASH_KEYWORD_WIFI = -5583; const int16_t HASH_KEYWORD_WIFI = -5583;
const int16_t HASH_KEYWORD_ETHERNET = -30767; const int16_t HASH_KEYWORD_ETHERNET = -30767;
const int16_t HASH_KEYWORD_WIT = 31594; 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]; int16_t DCCEXParser::stashP[MAX_COMMAND_PARAMS];
bool DCCEXParser::stashBusy; bool DCCEXParser::stashBusy;
@ -553,131 +547,69 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
case '1': // POWERON <1 [MAIN|PROG|JOIN]> case '1': // POWERON <1 [MAIN|PROG|JOIN]>
{ {
bool main=false; bool main=false;
bool prog=false; bool prog=false;
bool join=false; bool join=false;
bool singletrack=false; if (params > 1) break;
//byte t=0; if (params==0) { // All
if (params > 1) break; main=true;
if (params==0) { // All prog=true;
main=true; }
prog=true; if (params==1) {
} if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN>
if (params==1) { main=true;
if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN> }
main=true;
}
#ifndef DISABLE_PROG #ifndef DISABLE_PROG
else if (p[0] == HASH_KEYWORD_JOIN) { // <1 JOIN> else if (p[0] == HASH_KEYWORD_JOIN) { // <1 JOIN>
main=true; main=true;
prog=true; prog=true;
join=true; join=true;
} }
else if (p[0]==HASH_KEYWORD_PROG) { // <1 PROG> else if (p[0]==HASH_KEYWORD_PROG) { // <1 PROG>
prog=true; prog=true;
} }
#endif #endif
//else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> else break; // will reply <X>
else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H> }
byte t = (p[0] - 'A'); TrackManager::setJoin(join);
//DIAG(F("Processing track - %d "), t); if (main) TrackManager::setMainPower(POWERMODE::ON);
if (TrackManager::isProg(t)) { if (prog) TrackManager::setProgPower(POWERMODE::ON);
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> CommandDistributor::broadcastPower();
} return;
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] > case '0': // POWEROFF <0 [MAIN | PROG] >
{ {
bool main=false; bool main=false;
bool prog=false; bool prog=false;
bool singletrack=false; if (params > 1) break;
//byte t=0; if (params==0) { // All
if (params > 1) break; main=true;
if (params==0) { // All prog=true;
main=true; }
prog=true; if (params==1) {
} if (p[0]==HASH_KEYWORD_MAIN) { // <0 MAIN>
if (params==1) { main=true;
if (p[0]==HASH_KEYWORD_MAIN) { // <0 MAIN> }
main=true; #ifndef DISABLE_PROG
} else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG>
#ifndef DISABLE_PROG prog=true;
else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG> }
prog=true; #endif
} else break; // will reply <X>
#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> TrackManager::setJoin(false);
byte t = (p[0] - 'A'); if (main) TrackManager::setMainPower(POWERMODE::OFF);
//DIAG(F("Processing track - %d "), t); if (prog) {
if (TrackManager::isProg(t)) { TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off
main = false; TrackManager::setProgPower(POWERMODE::OFF);
prog = true; }
}
else CommandDistributor::broadcastPower();
{ return;
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 <!> case '!': // ESTOP ALL <!>
DCC::setThrottle(0,1,1); // this broadcasts speed 1(estop) and sets all reminders to speed 1. DCC::setThrottle(0,1,1); // this broadcasts speed 1(estop) and sets all reminders to speed 1.
@ -805,15 +737,11 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
SENDFLASHLIST(stream,RMFT2::rosterIdList) SENDFLASHLIST(stream,RMFT2::rosterIdList)
} }
else { else {
auto rosterName= RMFT2::getRosterName(id); const FSH * functionNames= RMFT2::getRosterFunctions(id);
if (!rosterName) rosterName=F(""); StringFormatter::send(stream,F(" %d \"%S\" \"%S\""),
id, RMFT2::getRosterName(id),
auto functionNames= RMFT2::getRosterFunctions(id); functionNames == NULL ? RMFT2::getRosterFunctions(0) : functionNames);
if (!functionNames) functionNames=RMFT2::getRosterFunctions(0); }
if (!functionNames) functionNames=F("");
StringFormatter::send(stream,F(" %d \"%S\" \"%S\""),
id, rosterName, functionNames);
}
#endif #endif
StringFormatter::send(stream, F(">\n")); StringFormatter::send(stream, F(">\n"));
return; return;
@ -842,70 +770,11 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream)
} }
StringFormatter::send(stream, F(">\n")); StringFormatter::send(stream, F(">\n"));
return; 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; default: break;
} // switch(p[1]) } // switch(p[1])
break; // case J 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 case 'L': // LCC interface implemented in EXRAIL parser
break; // Will <X> if not intercepted by EXRAIL break; // Will <X> if not intercepted by EXRAIL
@ -1127,7 +996,7 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
case HASH_KEYWORD_RAM: // <D RAM> case HASH_KEYWORD_RAM: // <D RAM>
StringFormatter::send(stream, F("Free memory=%d\n"), DCCTimer::getMinimumFreeMemory()); StringFormatter::send(stream, F("Free memory=%d\n"), DCCTimer::getMinimumFreeMemory());
return true; break;
#ifndef DISABLE_PROG #ifndef DISABLE_PROG
case HASH_KEYWORD_ACK: // <D ACK ON/OFF> <D ACK [LIMIT|MIN|MAX|RETRY] Value> case HASH_KEYWORD_ACK: // <D ACK ON/OFF> <D ACK [LIMIT|MIN|MAX|RETRY] Value>
@ -1228,99 +1097,6 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
return false; 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 // CALLBACKS must be static
bool DCCEXParser::stashCallback(Print *stream, int16_t p[MAX_COMMAND_PARAMS], RingStream * ringStream) bool DCCEXParser::stashCallback(Print *stream, int16_t p[MAX_COMMAND_PARAMS], RingStream * ringStream)
{ {

View File

@ -24,7 +24,6 @@
#include <Arduino.h> #include <Arduino.h>
#include "FSH.h" #include "FSH.h"
#include "RingStream.h" #include "RingStream.h"
#include "defines.h"
typedef void (*FILTER_CALLBACK)(Print * stream, byte & opcode, byte & paramCount, int16_t p[]); typedef void (*FILTER_CALLBACK)(Print * stream, byte & opcode, byte & paramCount, int16_t p[]);
typedef void (*AT_COMMAND_CALLBACK)(HardwareSerial * stream,const byte * command); typedef void (*AT_COMMAND_CALLBACK)(HardwareSerial * stream,const byte * command);
@ -46,16 +45,13 @@ struct DCCEXParser
static int16_t splitValues( int16_t result[MAX_COMMAND_PARAMS], const byte * command, bool usehex); static int16_t splitValues( int16_t result[MAX_COMMAND_PARAMS], const byte * command, bool usehex);
static bool parseT(Print * stream, int16_t params, int16_t p[]); static bool parseT(Print * stream, int16_t params, int16_t p[]);
static bool parseZ(Print * stream, int16_t params, int16_t p[]); static bool parseZ(Print * stream, int16_t params, int16_t p[]);
static bool parseS(Print * stream, int16_t params, int16_t p[]); static bool parseS(Print * stream, int16_t params, int16_t p[]);
static bool parsef(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[]); 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 Print * getAsyncReplyStream();
static void commitAsyncReplyStream(); static void commitAsyncReplyStream();
static bool stashBusy; static bool stashBusy;
static byte stashTarget; static byte stashTarget;

View File

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

View File

@ -1,6 +1,6 @@
/* /*
* © 2023 Neil McKechnie * © 2023 Neil McKechnie
* © 2022-2023 Paul M. Antoine * © 2022-23 Paul M. Antoine
* © 2021 Mike S * © 2021 Mike S
* © 2021, 2023 Harald Barth * © 2021, 2023 Harald Barth
* © 2021 Fred Decker * © 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 Serial3(PC11, PC10); // Rx=PC11, Tx=PC10 -- USART3 - F446RE
HardwareSerial Serial5(PD2, PC12); // Rx=PC7, Tx=PC6 -- UART5 - 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 // On the F446RE, Serial4 and Serial6 also use pins we can't readily map while using the Arduino pins
#elif defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) #elif defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)|| defined(ARDUINO_NUCLEO_F412ZG)
// Nucleo-144 boards don't have Serial1 defined by default // Nucleo-144 boards don't have Serial1 defined by default
HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6 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 // Serial3 is defined to use USART3 by default, but is in fact used as the diag console
@ -154,28 +154,13 @@ HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6
/////////////////////////////////////////////////////////////////////////////////////////////// ///////////////////////////////////////////////////////////////////////////////////////////////
INTERRUPT_CALLBACK interruptHandler=0; INTERRUPT_CALLBACK interruptHandler=0;
// Let's use STM32's timer #11 until disabused of this notion
// On STM32F4xx models that have them, Timers 6 and 7 have no PWM output capability, // Timer #11 is used for "servo" library, but as DCC-EX is not using
// so are good choices for general timer duties - they are used for tone and servo // this libary, we should be free and clear.
// in stm32duino so we shall usurp those as DCC-EX doesn't use tone or servo libs. HardwareTimer timer(TIM11);
// 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 // Timer IRQ handler
void DCCTimer_Handler() { void Timer11_Handler() {
interruptHandler(); interruptHandler();
} }
@ -183,24 +168,22 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
interruptHandler=callback; interruptHandler=callback;
noInterrupts(); noInterrupts();
dcctimer.pause(); // adc_set_sample_rate(ADC_SAMPLETIME_480CYCLES);
dcctimer.setPrescaleFactor(1); timer.pause();
timer.setPrescaleFactor(1);
// timer.setOverflow(CLOCK_CYCLES * 2); // timer.setOverflow(CLOCK_CYCLES * 2);
dcctimer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT); timer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT);
// dcctimer.attachInterrupt(Timer11_Handler); timer.attachInterrupt(Timer11_Handler);
dcctimer.attachInterrupt(DCCTimer_Handler); timer.refresh();
dcctimer.setInterruptPriority(0, 0); // Set highest preemptive priority! timer.resume();
dcctimer.refresh();
dcctimer.resume();
interrupts(); interrupts();
} }
bool DCCTimer::isPWMPin(byte pin) { bool DCCTimer::isPWMPin(byte pin) {
//TODO: STM32 whilst this call to digitalPinHasPWM will reveal which pins can do PWM, //TODO: SAMD 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 // there's no support yet for High Accuracy, so for now return false
// return digitalPinHasPWM(pin); // return digitalPinHasPWM(pin);
(void) pin;
return false; return false;
} }
@ -252,91 +235,22 @@ void DCCTimer::reset() {
while(true) {}; while(true) {};
} }
// TODO: rationalise the size of these... could really use sparse arrays etc. // TODO: may need to use uint32_t on STMF4xx variants with > 16 analog inputs!
static HardwareTimer * pin_timer[100] = {0}; #if defined(ARDUINO_NUCLEO_F446RE) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)
static uint32_t channel_frequency[100] = {0}; #warning STM32 board selected not fully supported - only use ADC1 inputs 0-15 for current sensing!
static uint32_t pin_channel[100] = {0}; #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
// Using the HardwareTimer library API included in stm32duino core to handle PWM duties uint16_t ADCee::usedpins = 0;
// TODO: in order to use the HA code above which Neil kindly wrote, we may have to do something more uint8_t ADCee::highestPin = 0;
// sophisticated about detecting any clash between the timer we'd like to use for PWM and the ones int * ADCee::analogvals = NULL;
// currently used for HA so they don't interfere with one another. For now we'll just make PWM uint32_t * analogchans = NULL;
// work well... then work backwards to integrate with HA mode if we can. bool adc1configured = false;
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));
// Instantiate HardwareTimer object. Thanks to 'new' instantiation, int16_t ADCee::ADCmax() {
// HardwareTimer is not destructed when setup function is finished. return 4095;
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;
} }
int ADCee::init(uint8_t pin) { int ADCee::init(uint8_t pin) {
@ -347,33 +261,11 @@ int ADCee::init(uint8_t pin) {
return -1024; // some silly value as error 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 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 input channel uint32_t adcchan = STM_PIN_CHANNEL(pinmap_function(stmpin, PinMap_ADC)); // find ADC channel (only valid for ADC1!)
ADC_TypeDef *adc = (ADC_TypeDef *)pinmap_find_peripheral(stmpin, PinMap_ADC); // find which ADC this pin is on ADC1/2/3 etc. GPIO_TypeDef * gpioBase;
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 // Port config - find which port we're on and power it up
GPIO_TypeDef *gpioBase; switch(stmgpio) {
switch (stmgpio)
{
case 0x00: case 0x00:
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; //Power up PORTA RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; //Power up PORTA
gpioBase = GPIOA; gpioBase = GPIOA;
@ -386,20 +278,6 @@ int ADCee::init(uint8_t pin) {
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN; //Power up PORTC RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN; //Power up PORTC
gpioBase = GPIOC; gpioBase = GPIOC;
break; 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: default:
return -1023; // some silly value as error return -1023; // some silly value as error
} }
@ -415,33 +293,31 @@ int ADCee::init(uint8_t pin) {
if (adcchan > 18) if (adcchan > 18)
return -1022; // silly value as error return -1022; // silly value as error
if (adcchan < 10) if (adcchan < 10)
adc->SMPR2 |= (0b111 << (adcchan * 3)); // Channel sampling rate 480 cycles ADC1->SMPR2 |= (0b111 << (adcchan * 3)); // Channel sampling rate 480 cycles
else else
adc->SMPR1 |= (0b111 << ((adcchan - 10) * 3)); // Channel sampling rate 480 cycles ADC1->SMPR1 |= (0b111 << ((adcchan - 10) * 3)); // Channel sampling rate 480 cycles
// Read the inital ADC value for this analog input // Read the inital ADC value for this analog input
adc->SQR3 = adcchan; // 1st conversion in regular sequence ADC1->SQR3 = adcchan; // 1st conversion in regular sequence
adc->CR2 |= ADC_CR2_SWSTART; //(1 << 30); // Start 1st conversion SWSTART ADC1->CR2 |= (1 << 30); // Start 1st conversion SWSTART
while(!(adc->SR & (1 << 1))); // Wait until conversion is complete while(!(ADC1->SR & (1 << 1))); // Wait until conversion is complete
value = adc->DR; // Read value from register value = ADC1->DR; // Read value from register
uint8_t id = pin - PNUM_ANALOG_BASE; uint8_t id = pin - PNUM_ANALOG_BASE;
// if (id > 15) { // today we have not enough bits in the mask to support more if (id > 15) { // today we have not enough bits in the mask to support more
// return -1021; return -1021;
// } }
if (analogvals == NULL) { // allocate analogvals, analogchans and adcchans if this is the first invocation of init if (analogvals == NULL) { // allocate analogvals and analogchans if this is the first invocation of init.
analogvals = (int *)calloc(NUM_ADC_INPUTS+1, sizeof(int)); analogvals = (int *)calloc(NUM_ADC_INPUTS+1, sizeof(int));
analogchans = (uint32_t *)calloc(NUM_ADC_INPUTS+1, sizeof(uint32_t)); 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 analogvals[id] = value; // Store sampled value
analogchans[id] = adcchan; // Keep track of which ADC channel is used for reading this pin 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
usedpins |= (1 << id); // This pin is now ready
if (id > highestPin) highestPin = id; // Store our highest pin in use if (id > highestPin) highestPin = id; // Store our highest pin in use
DIAG(F("ADCee::init(): value=%d, ADC%d: channel=%d, id=%d"), value, adcnum, adcchan, id); DIAG(F("ADCee::init(): value=%d, channel=%d, id=%d"), value, adcchan, id);
return value; return value;
} }
@ -468,16 +344,13 @@ void ADCee::scan() {
static uint8_t id = 0; // id and mask are the same thing but it is faster to static uint8_t id = 0; // id and mask are the same thing but it is faster to
static uint16_t mask = 1; // increment and shift instead to calculate mask from id static uint16_t mask = 1; // increment and shift instead to calculate mask from id
static bool waiting = false; static bool waiting = false;
static ADC_TypeDef *adc;
adc = adcchans[id]; if (waiting) {
if (waiting)
{
// look if we have a result // look if we have a result
if (!(adc->SR & (1 << 1))) if (!(ADC1->SR & (1 << 1)))
return; // no result, continue to wait return; // no result, continue to wait
// found value // found value
analogvals[id] = adc->DR; analogvals[id] = ADC1->DR;
// advance at least one track // advance at least one track
#ifdef DEBUG_ADC #ifdef DEBUG_ADC
if (id == 1) TrackManager::track[1]->setBrake(0); if (id == 1) TrackManager::track[1]->setBrake(0);
@ -496,10 +369,9 @@ void ADCee::scan() {
// look for a valid track to sample or until we are around // look for a valid track to sample or until we are around
while (true) { while (true) {
if (mask & usedpins) { if (mask & usedpins) {
// start new ADC aquire on id // start new ADC aquire on id
adc = adcchans[id]; ADC1->SQR3 = analogchans[id]; //1st conversion in regular sequence
adc->SQR3 = analogchans[id]; // 1st conversion in regular sequence ADC1->CR2 |= (1 << 30); //Start 1st conversion SWSTART
adc->CR2 |= (1 << 30); // Start 1st conversion SWSTART
#ifdef DEBUG_ADC #ifdef DEBUG_ADC
if (id == 1) TrackManager::track[1]->setBrake(1); if (id == 1) TrackManager::track[1]->setBrake(1);
#endif #endif
@ -520,83 +392,19 @@ void ADCee::scan() {
void ADCee::begin() { void ADCee::begin() {
noInterrupts(); noInterrupts();
//ADC1 config sequence //ADC1 config sequence
RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; // Enable ADC1 clock // TODO: currently defaults to ADC1, may need more to handle other members of STM32F4xx family
RCC->APB2ENR |= (1 << 8); //Enable ADC1 clock (Bit8)
// Set ADC prescaler - DIV8 ~ 40ms, DIV6 ~ 30ms, DIV4 ~ 20ms, DIV2 ~ 11ms // 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 ADC->CCR = (0 << 16); // Set prescaler 0=DIV2, 1=DIV4, 2=DIV6, 3=DIV8
ADC1->CR1 &= ~(1 << 8); //SCAN mode disabled (Bit8) ADC1->CR1 &= ~(1 << 8); //SCAN mode disabled (Bit8)
ADC1->CR1 &= ~(3 << 24); //12bit resolution (Bit24,25 0b00) ADC1->CR1 &= ~(3 << 24); //12bit resolution (Bit24,25 0b00)
ADC1->SQR1 = (1 << 20); //Set number of conversions projected (L[3:0] 0b0001) -> 1 conversion ADC1->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 << 1); //Single conversion
ADC1->CR2 &= ~(1 << 11); //Right alignment of data bits bit12....bit0 ADC1->CR2 &= ~(1 << 11); //Right alignment of data bits bit12....bit0
ADC1->SQR1 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register ADC1->SQR1 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register
ADC1->SQR2 &= ~(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->SQR3 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register
ADC1->CR2 |= (1 << 0); // Switch on ADC1 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(); interrupts();
} }
#endif #endif

View File

@ -52,8 +52,6 @@
#include "Turnouts.h" #include "Turnouts.h"
#include "CommandDistributor.h" #include "CommandDistributor.h"
#include "TrackManager.h" #include "TrackManager.h"
#include "Turntables.h"
#include "IODevice.h"
// Command parsing keywords // Command parsing keywords
const int16_t HASH_KEYWORD_EXRAIL=15435; const int16_t HASH_KEYWORD_EXRAIL=15435;
@ -99,9 +97,6 @@ LookList * RMFT2::onAmberLookup=NULL;
LookList * RMFT2::onGreenLookup=NULL; LookList * RMFT2::onGreenLookup=NULL;
LookList * RMFT2::onChangeLookup=NULL; LookList * RMFT2::onChangeLookup=NULL;
LookList * RMFT2::onClockLookup=NULL; LookList * RMFT2::onClockLookup=NULL;
#ifndef IO_NO_HAL
LookList * RMFT2::onRotateLookup=NULL;
#endif
LookList * RMFT2::onOverloadLookup=NULL; LookList * RMFT2::onOverloadLookup=NULL;
#define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter) #define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter)
@ -181,9 +176,6 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
onDeactivateLookup=LookListLoader(OPCODE_ONDEACTIVATE); onDeactivateLookup=LookListLoader(OPCODE_ONDEACTIVATE);
onChangeLookup=LookListLoader(OPCODE_ONCHANGE); onChangeLookup=LookListLoader(OPCODE_ONCHANGE);
onClockLookup=LookListLoader(OPCODE_ONTIME); onClockLookup=LookListLoader(OPCODE_ONTIME);
#ifndef IO_NO_HAL
onRotateLookup=LookListLoader(OPCODE_ONROTATE);
#endif
onOverloadLookup=LookListLoader(OPCODE_ONOVERLOAD); onOverloadLookup=LookListLoader(OPCODE_ONOVERLOAD);
// onLCCLookup is not the same so not loaded here. // onLCCLookup is not the same so not loaded here.
@ -255,38 +247,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) {
setTurnoutHiddenState(VpinTurnout::create(id,pin)); setTurnoutHiddenState(VpinTurnout::create(id,pin));
break; 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: case OPCODE_AUTOSTART:
// automatically create a task from here at startup. // automatically create a task from here at startup.
// Removed if (progCounter>0) check 4.2.31 because // Removed if (progCounter>0) check 4.2.31 because
@ -311,12 +272,6 @@ void RMFT2::setTurnoutHiddenState(Turnout * t) {
t->setHidden(GETFLASH(getTurnoutDescription(t->getId()))==0x01); 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) { char RMFT2::getRouteType(int16_t id) {
for (int16_t i=0;;i+=2) { for (int16_t i=0;;i+=2) {
int16_t rid= GETHIGHFLASHW(routeIdList,i); int16_t rid= GETHIGHFLASHW(routeIdList,i);
@ -709,14 +664,6 @@ void RMFT2::loop2() {
Turnout::setClosed(operand, true); Turnout::setClosed(operand, true);
break; 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: case OPCODE_REV:
forward = false; forward = false;
driveLoco(operand); driveLoco(operand);
@ -843,20 +790,6 @@ void RMFT2::loop2() {
TrackManager::setJoin(false); TrackManager::setJoin(false);
CommandDistributor::broadcastPower(); CommandDistributor::broadcastPower();
break; 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: case OPCODE_SET_TRACK:
// operand is trackmode<<8 | track id // operand is trackmode<<8 | track id
@ -930,13 +863,7 @@ void RMFT2::loop2() {
case OPCODE_IFCLOSED: case OPCODE_IFCLOSED:
skipIf=Turnout::isThrown(operand); skipIf=Turnout::isThrown(operand);
break; 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: case OPCODE_ENDIF:
break; break;
@ -1123,16 +1050,7 @@ void RMFT2::loop2() {
return; return;
} }
break; 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: case OPCODE_PRINT:
printMessage(operand); printMessage(operand);
break; break;
@ -1158,12 +1076,6 @@ void RMFT2::loop2() {
case OPCODE_ONGREEN: case OPCODE_ONGREEN:
case OPCODE_ONCHANGE: case OPCODE_ONCHANGE:
case OPCODE_ONTIME: 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: case OPCODE_ONOVERLOAD:
break; break;
@ -1287,7 +1199,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) {
} }
/* static */ bool RMFT2::isSignal(int16_t id,char rag) { /* static */ bool RMFT2::isSignal(int16_t id,char rag) {
if (!(compileFeatures & FEATURE_SIGNAL)) return false; if (!(compileFeatures & FEATURE_LCC)) return false;
int16_t sigslot=getSignalSlot(id); int16_t sigslot=getSignalSlot(id);
if (sigslot<0) return false; if (sigslot<0) return false;
return (flags[sigslot] & SIGNAL_MASK) == rag; return (flags[sigslot] & SIGNAL_MASK) == rag;
@ -1311,13 +1223,6 @@ void RMFT2::changeEvent(int16_t vpin, bool change) {
if (change) handleEvent(F("CHANGE"),onChangeLookup,vpin); 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) { void RMFT2::clockEvent(int16_t clocktime, bool change) {
// Hunt for an ONTIME for this time // Hunt for an ONTIME for this time
if (Diag::CMD) if (Diag::CMD)

View File

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

View File

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

View File

@ -54,8 +54,6 @@
// helper macro for turnout descriptions, creates NULL for missing description // helper macro for turnout descriptions, creates NULL for missing description
#define O_DESC(id, desc) case id: return ("" desc)[0]?F("" desc):NULL; #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 // helper macro for turnout description as HIDDEN
#define HIDDEN "\x01" #define HIDDEN "\x01"
@ -63,24 +61,16 @@
// (10#mins)%100) // (10#mins)%100)
#define STRIP_ZERO(value) 10##value%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 // Pass 1 Implements aliases
#include "EXRAIL2MacroReset.h" #include "EXRAIL2MacroReset.h"
#undef ALIAS #undef ALIAS
#define ALIAS(name,value...) const int name= 1##value##0 ==10 ? -__COUNTER__ : value##0/10; #define ALIAS(name,value...) const int name= 1##value##0 ==10 ? -__COUNTER__ : value##0/10;
#include "myAutomation.h" #include "myAutomation.h"
// Pass 1h Implements HAL macro by creating exrailHalSetup function // Pass 1h Implements HAL macro by creating exrailHalSetup function
// Also allows creating EXTurntable object
#include "EXRAIL2MacroReset.h" #include "EXRAIL2MacroReset.h"
#undef HAL #undef HAL
#define HAL(haltype,params...) haltype::create(params); #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() { void exrailHalSetup() {
#include "myAutomation.h" #include "myAutomation.h"
} }
@ -221,31 +211,6 @@ const FSH * RMFT2::getTurnoutDescription(int16_t turnoutid) {
return NULL; 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) // Pass 6: Roster IDs (count)
#include "EXRAIL2MacroReset.h" #include "EXRAIL2MacroReset.h"
#undef ROSTER #undef ROSTER
@ -338,9 +303,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define BROADCAST(msg) PRINT(msg) #define BROADCAST(msg) PRINT(msg)
#define CALL(route) OPCODE_CALL,V(route), #define CALL(route) OPCODE_CALL,V(route),
#define CLOSE(id) OPCODE_CLOSE,V(id), #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 DEACTIVATE(addr,subaddr) OPCODE_DCCACTIVATE,V(addr<<3 | subaddr<<1),
#define DEACTIVATEL(addr) OPCODE_DCCACTIVATE,V((addr+3)<<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)), #define DELAY(ms) ms<30000?OPCODE_DELAYMS:OPCODE_DELAY,V(ms/(ms<30000?1L:100L)),
@ -354,10 +316,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define ENDIF OPCODE_ENDIF,0,0, #define ENDIF OPCODE_ENDIF,0,0,
#define ENDTASK OPCODE_ENDTASK,0,0, #define ENDTASK OPCODE_ENDTASK,0,0,
#define ESTOP OPCODE_SPEED,V(1), #define ESTOP OPCODE_SPEED,V(1),
#define EXRAIL #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 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 FOFF(func) OPCODE_FOFF,V(func),
#define FOLLOW(route) OPCODE_FOLLOW,V(route), #define FOLLOW(route) OPCODE_FOLLOW,V(route),
@ -380,9 +339,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define IFRESERVE(block) OPCODE_IFRESERVE,V(block), #define IFRESERVE(block) OPCODE_IFRESERVE,V(block),
#define IFTHROWN(turnout_id) OPCODE_IFTHROWN,V(turnout_id), #define IFTHROWN(turnout_id) OPCODE_IFTHROWN,V(turnout_id),
#define IFTIMEOUT OPCODE_IFTIMEOUT,0,0, #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 IFRE(sensor_id,value) OPCODE_IFRE,V(sensor_id),OPCODE_PAD,V(value),
#define INVERT_DIRECTION OPCODE_INVERT_DIRECTION,0,0, #define INVERT_DIRECTION OPCODE_INVERT_DIRECTION,0,0,
#define JOIN OPCODE_JOIN,0,0, #define JOIN OPCODE_JOIN,0,0,
@ -413,9 +369,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define ONDEACTIVATEL(linear) OPCODE_ONDEACTIVATE,V(linear+3), #define ONDEACTIVATEL(linear) OPCODE_ONDEACTIVATE,V(linear+3),
#define ONGREEN(signal_id) OPCODE_ONGREEN,V(signal_id), #define ONGREEN(signal_id) OPCODE_ONGREEN,V(signal_id),
#define ONRED(signal_id) OPCODE_ONRED,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 ONTHROW(turnout_id) OPCODE_ONTHROW,V(turnout_id),
#define ONCHANGE(sensor_id) OPCODE_ONCHANGE,V(sensor_id), #define ONCHANGE(sensor_id) OPCODE_ONCHANGE,V(sensor_id),
#define PAUSE OPCODE_PAUSE,0,0, #define PAUSE OPCODE_PAUSE,0,0,
@ -435,10 +388,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define RETURN OPCODE_RETURN,0,0, #define RETURN OPCODE_RETURN,0,0,
#define REV(speed) OPCODE_REV,V(speed), #define REV(speed) OPCODE_REV,V(speed),
#define ROSTER(cabid,name,funcmap...) #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 ROUTE(id, description) OPCODE_ROUTE, V(id),
#define SENDLOCO(cab,route) OPCODE_SENDLOCO,V(cab),OPCODE_PAD,V(route), #define SENDLOCO(cab,route) OPCODE_SENDLOCO,V(cab),OPCODE_PAD,V(route),
#define SEQUENCE(id) OPCODE_SEQUENCE, V(id), #define SEQUENCE(id) OPCODE_SEQUENCE, V(id),
@ -455,17 +404,13 @@ 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 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(pin) OPCODE_SET,V(pin),
#define SET_TRACK(track,mode) OPCODE_SET_TRACK,V(TRACK_MODE_##mode <<8 | TRACK_NUMBER_##track), #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 SETLOCO(loco) OPCODE_SETLOCO,V(loco),
#define SIGNAL(redpin,amberpin,greenpin) #define SIGNAL(redpin,amberpin,greenpin)
#define SIGNALH(redpin,amberpin,greenpin) #define SIGNALH(redpin,amberpin,greenpin)
#define SPEED(speed) OPCODE_SPEED,V(speed), #define SPEED(speed) OPCODE_SPEED,V(speed),
#define START(route) OPCODE_START,V(route), #define START(route) OPCODE_START,V(route),
#define STOP OPCODE_SPEED,V(0), #define STOP OPCODE_SPEED,V(0),
#define THROW(id) OPCODE_THROW,V(id), #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 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 TURNOUTL(id,addr,description...) TURNOUT(id,(addr-1)/4+1,(addr-1)%4, description)
#define UNJOIN OPCODE_UNJOIN,0,0, #define UNJOIN OPCODE_UNJOIN,0,0,
@ -474,9 +419,6 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup];
#define VIRTUAL_TURNOUT(id,description...) OPCODE_PINTURNOUT,V(id),OPCODE_PAD,V(0), #define VIRTUAL_TURNOUT(id,description...) OPCODE_PINTURNOUT,V(id),OPCODE_PAD,V(0),
#define WITHROTTLE(msg) PRINT(msg) #define WITHROTTLE(msg) PRINT(msg)
#define WAITFOR(pin) OPCODE_WAITFOR,V(pin), #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 XFOFF(cab,func) OPCODE_XFOFF,V(cab),OPCODE_PAD,V(func),
#define XFON(cab,func) OPCODE_XFON,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-202309241855Z" #define GITHUB_SHA "devel-202308302157Z"

View File

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

View File

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

View File

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

View File

@ -26,44 +26,27 @@
#include "I2CManager.h" #include "I2CManager.h"
#include "I2CManager_NonBlocking.h" // to satisfy intellisense #include "I2CManager_NonBlocking.h" // to satisfy intellisense
//#include <avr/io.h>
//#include <avr/interrupt.h>
#include <wiring_private.h> #include <wiring_private.h>
#include "stm32f4xx_hal_rcc.h"
/***************************************************************************** /***************************************************************************
* STM32F4xx I2C native driver support * Interrupt handler.
* * IRQ handler for SERCOM3 which is the default I2C definition for Arduino Zero
* Nucleo-64 and Nucleo-144 boards all use I2C1 as the default I2C peripheral * compatible variants such as the Sparkfun SAMD21 Dev Breakout etc.
* Later we may wish to support other STM32 boards, allow use of an alternate * Later we may wish to allow use of an alternate I2C bus, or more than one I2C
* I2C bus, or more than one I2C bus on the STM32 architecture * bus on the SAMD architecture
*****************************************************************************/ ***************************************************************************/
#if defined(I2C_USE_INTERRUPTS) && defined(ARDUINO_ARCH_STM32) #if defined(I2C_USE_INTERRUPTS) && defined(ARDUINO_ARCH_STM32)
#if defined(ARDUINO_NUCLEO_F401RE) || defined(ARDUINO_NUCLEO_F411RE) || defined(ARDUINO_NUCLEO_F446RE) \ void I2C1_IRQHandler() {
|| defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F413ZH) \ I2CManager.handleInterrupt();
|| defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) }
// Assume I2C1 for now - default I2C bus on Nucleo-F411RE and likely all Nucleo-64 #endif
// and Nucleo-144 variants
// Assume I2C1 for now - default I2C bus on Nucleo-F411RE and likely Nucleo-64 variants
I2C_TypeDef *s = I2C1; I2C_TypeDef *s = I2C1;
#define I2C_IRQn I2C1_EV_IRQn
// In init we will ask the STM32 HAL layer for the configured APB1 clock frequency in Hz #define I2C_BUSFREQ 16
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
// 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 // I2C SR1 Status Register #1 bit definitions for convenience
// #define I2C_SR1_SMBALERT (1<<15) // SMBus alert // #define I2C_SR1_SMBALERT (1<<15) // SMBus alert
@ -97,66 +80,52 @@ extern "C" void I2C1_ER_IRQHandler(void) {
// #define I2C_CR1_SMBUS (1<<1) // SMBus mode, 1=SMBus, 0=I2C // #define I2C_CR1_SMBUS (1<<1) // SMBus mode, 1=SMBus, 0=I2C
// #define I2C_CR1_PE (1<<0) // I2C Peripheral enable // #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 * Set I2C clock speed register. This should only be called outside of
* a transmission. The I2CManagerClass::_setClock() function ensures * a transmission. The I2CManagerClass::_setClock() function ensures
* that it is only called at the beginning of an I2C transaction. * that it is only called at the beginning of an I2C transaction.
***************************************************************************/ ***************************************************************************/
void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) {
// Calculate a rise time appropriate to the requested bus speed // Calculate a rise time appropriate to the requested bus speed
// Use 10x the rise time spec to enable integer divide of 50ns clock period // Use 10x the rise time spec to enable integer divide of 62.5ns clock period
uint16_t t_rise; uint16_t t_rise;
uint32_t ccr_freq; uint32_t ccr_freq;
if (i2cClockSpeed < 200000L) {
while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further // i2cClockSpeed = 100000L;
// writes to CR1 while STOP is being executed! t_rise = 0x11; // (1000ns /62.5ns) + 1;
}
// Disable the I2C device, as TRISE can only be programmed whilst disabled else if (i2cClockSpeed < 800000L)
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)
{ {
// if (i2cClockSpeed > 400000L) i2cClockSpeed = 400000L;
// i2cClockSpeed = 400000L; t_rise = 0x06; // (300ns / 62.5ns) + 1;
// } else if (i2cClockSpeed < 1200000L) {
t_rise = 300; // nanoseconds // i2cClockSpeed = 1000000L;
// t_rise = 120;
} }
else else
{ {
// i2cClockSpeed = 100000L; i2cClockSpeed = 100000L;
t_rise = 1000; // nanoseconds t_rise = 0x11; // (1000ns /62.5ns) + 1;
} }
// Configure the rise time register - max allowed tRISE is 1000ns,
// so value = 1000ns * I2C_PERIPH_CLK MHz / 1000 + 1. // Enable the I2C master mode
s->TRISE = (t_rise * i2c_MHz / 1000) + 1; 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;
// Bit 15: I2C Master mode, 0=standard, 1=Fast Mode // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode
// Bit 14: Duty, fast mode duty cycle (use 2:1) // Bit 14: Duty, fast mode duty cycle
// Bit 11-0: FREQR // Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns, so CCR divisor must be 0x50 (80 * 62.5ns = 5000ns)
// if (i2cClockSpeed > 400000UL) { s->CCR = (uint16_t)ccr_freq;
// // 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
// }
// DIAG(F("I2C_init() peripheral clock is now: %d, full reg is %x"), (s->CR2 & 0xFF), s->CR2); // Configure the rise time register
// DIAG(F("I2C_init() peripheral CCR is now: %d"), s->CCR); s->TRISE = t_rise; // 1000 ns / 62.5 ns = 16 + 1
// DIAG(F("I2C_init() peripheral TRISE is now: %d"), s->TRISE);
// Enable the I2C master mode // Enable the I2C master mode
s->CR1 |= I2C_CR1_PE; // Enable I2C s->CR1 |= I2C_CR1_PE; // Enable I2C
@ -167,54 +136,32 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) {
***************************************************************************/ ***************************************************************************/
void I2CManagerClass::I2C_init() void I2CManagerClass::I2C_init()
{ {
// Query the clockspeed from the STM32 HAL layer //Setting up the clocks
APB1clk1 = HAL_RCC_GetPCLK1Freq(); RCC->APB1ENR |= (1<<21); // Enable I2C CLOCK
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 RCC->AHB1ENR |= (1<<1); // Enable GPIOB CLOCK for PB8/PB9
// Standard I2C pins are SCL on PB8 and SDA on PB9
// Bits (17:16)= 1:0 --> Alternate Function for Pin PB8; // Bits (17:16)= 1:0 --> Alternate Function for Pin PB8;
// Bits (19:18)= 1:0 --> Alternate Function for Pin PB9 // 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->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->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->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 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: // 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 (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 // 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 GPIOB->AFR[1] |= (4<<0) | (4<<4); // PB8 on low nibble, PB9 on next nibble up
// Software reset the I2C peripheral // Software reset the I2C peripheral
I2C1->CR1 &= ~I2C_CR1_PE; // Disable I2C1 peripheral
s->CR1 |= I2C_CR1_SWRST; // reset the I2C s->CR1 |= I2C_CR1_SWRST; // reset the I2C
asm("nop"); // wait a bit... suggestion from online! s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation
s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation
// Clear all bits in I2C CR2 register except reserved bits // Program the peripheral input clock in CR2 Register in order to generate correct timings
s->CR2 &= 0xE000; s->CR2 |= I2C_BUSFREQ; // PCLK1 FREQUENCY in MHz
// 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) #if defined(I2C_USE_INTERRUPTS)
// Setting NVIC // Setting NVIC
NVIC_SetPriority(I2C1_EV_IRQn, 1); // Match default priorities NVIC_SetPriority(I2C_IRQn, 1); // Match default priorities
NVIC_EnableIRQ(I2C1_EV_IRQn); NVIC_EnableIRQ(I2C_IRQn);
NVIC_SetPriority(I2C1_ER_IRQn, 1); // Match default priorities
NVIC_EnableIRQ(I2C1_ER_IRQn);
// CR2 Interrupt Settings // CR2 Interrupt Settings
// Bit 15-13: reserved // Bit 15-13: reserved
@ -225,28 +172,23 @@ void I2CManagerClass::I2C_init()
// Bit 8: ITERREN - Error interrupt enable // Bit 8: ITERREN - Error interrupt enable
// Bit 7-6: reserved // Bit 7-6: reserved
// Bit 5-0: FREQ - Peripheral clock frequency (max 50MHz) // Bit 5-0: FREQ - Peripheral clock frequency (max 50MHz)
s->CR2 |= (I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN); // Enable Buffer, Event and Error interrupts // s->CR2 |= 0x0700; // Enable Buffer, Event and Error interrupts
s->CR2 |= 0x0300; // Enable Event and Error interrupts
#endif #endif
// DIAG(F("I2C_init() setting initial I2C clock to 100KHz"));
// Calculate baudrate and set default rate for now // Calculate baudrate and set default rate for now
// Configure the Clock Control Register for 100KHz SCL frequency // Configure the Clock Control Register for 100KHz SCL frequency
// Bit 15: I2C Master mode, 0=standard, 1=Fast Mode // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode
// Bit 14: Duty, fast mode duty cycle // Bit 14: Duty, fast mode duty cycle
// Bit 11-0: so CCR divisor would be clk / 2 / 100000 (where clk is in Hz) // Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns, so CCR divisor must be 0x50 (80 * 62.5ns = 5000ns)
// s->CCR = I2C_PERIPH_CLK * 5; s->CCR = 0x0050;
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 is 1000ns, so value = 1000ns * I2C_PERIPH_CLK MHz / 1000 + 1. // Configure the rise time register - max allowed in 1000ns
s->TRISE = (1000 * i2c_MHz / 1000) + 1; s->TRISE = 0x0011; // 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 // Enable the I2C master mode
s->CR1 |= I2C_CR1_PE; // Enable I2C s->CR1 |= I2C_CR1_PE; // Enable I2C
// Setting bus idle mode and wait for sync
} }
/*************************************************************************** /***************************************************************************
@ -256,30 +198,49 @@ void I2CManagerClass::I2C_sendStart() {
// Set counters here in case this is a retry. // Set counters here in case this is a retry.
rxCount = txCount = 0; rxCount = txCount = 0;
uint8_t temp;
// On a single-master I2C bus, the start bit won't be sent until the bus // 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 // 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, // 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 // in which case we can avoid some arbitration failures by waiting until
// the bus state is IDLE. We don't do that here. // the bus state is IDLE. We don't do that here.
//while (s->SR2 & I2C_SR2_BUSY) {}
// Check there's no STOP still in progress. If we OR the START bit into CR1 // If anything to send, initiate write. Otherwise initiate read.
// and the STOP bit is already set, we could output multiple STOP conditions. if (operation == OPERATION_READ || ((operation == OPERATION_REQUEST) && !bytesToSend))
while (s->CR1 & I2C_CR1_STOP) {} // Wait for STOP bit to reset {
// Send start for read operation
s->CR2 |= (I2C_CR2_ITEVTEN | I2C_CR2_ITERREN); // Enable interrupts s->CR1 |= I2C_CR1_ACK; // Enable the ACK
s->CR2 &= ~I2C_CR2_ITBUFEN; // Don't enable buffer interupts yet. s->CR1 |= I2C_CR1_START; // Generate START
s->CR1 &= ~I2C_CR1_POS; // Clear the POS bit // Send address with read flag (1) or'd in
s->CR1 |= (I2C_CR1_ACK | I2C_CR1_START); // Enable the ACK and generate START s->DR = (deviceAddress << 1) | 1; // send the address
transactionState = TS_START; 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
}
} }
/*************************************************************************** /***************************************************************************
* Initiate a stop bit for transmission (does not interrupt) * Initiate a stop bit for transmission (does not interrupt)
***************************************************************************/ ***************************************************************************/
void I2CManagerClass::I2C_sendStop() { void I2CManagerClass::I2C_sendStop() {
s->CR1 |= I2C_CR1_STOP; // Stop I2C s->CR1 |= I2C_CR1_STOP; // Stop I2C
} }
/*************************************************************************** /***************************************************************************
@ -291,11 +252,9 @@ void I2CManagerClass::I2C_close() {
s->CR1 &= ~I2C_CR1_PE; // Disable I2C peripheral s->CR1 &= ~I2C_CR1_PE; // Disable I2C peripheral
// Should never happen, but wait for up to 500us only. // Should never happen, but wait for up to 500us only.
unsigned long startTime = micros(); unsigned long startTime = micros();
while ((s->CR1 & I2C_CR1_PE) != 0) { while ((s->CR1 && I2C_CR1_PE) != 0) {
if ((int32_t)(micros() - startTime) >= 500) break; if (micros() - startTime >= 500UL) break;
} }
NVIC_DisableIRQ(I2C1_EV_IRQn);
NVIC_DisableIRQ(I2C1_ER_IRQn);
} }
/*************************************************************************** /***************************************************************************
@ -304,217 +263,50 @@ void I2CManagerClass::I2C_close() {
* (and therefore, indirectly, from I2CRB::wait() and I2CRB::isBusy()). * (and therefore, indirectly, from I2CRB::wait() and I2CRB::isBusy()).
***************************************************************************/ ***************************************************************************/
void I2CManagerClass::I2C_handleInterrupt() { void I2CManagerClass::I2C_handleInterrupt() {
volatile uint16_t temp_sr1, temp_sr2;
temp_sr1 = s->SR1; if (s->SR1 && I2C_SR1_ARLO) {
// Arbitration lost, restart
// Check for errors first I2C_sendStart(); // Reinitiate request
if (temp_sr1 & (I2C_SR1_AF | I2C_SR1_ARLO | I2C_SR1_BERR)) { } else if (s->SR1 && I2C_SR1_BERR) {
// Check which error flag is set // Bus error
if (temp_sr1 & I2C_SR1_AF) completionStatus = I2C_STATUS_BUS_ERROR;
{ state = I2C_STATE_COMPLETED;
s->SR1 &= ~(I2C_SR1_AF); // Clear AF } else if (s->SR1 && I2C_SR1_TXE) {
I2C_sendStop(); // Clear the bus // Master write completed
transactionState = TS_IDLE; if (s->SR1 && (1<<10)) {
// Nacked, send stop.
I2C_sendStop();
completionStatus = I2C_STATUS_NEGATIVE_ACKNOWLEDGE; completionStatus = I2C_STATUS_NEGATIVE_ACKNOWLEDGE;
state = I2C_STATE_COMPLETED; state = I2C_STATE_COMPLETED;
} } else if (bytesToSend) {
else if (temp_sr1 & I2C_SR1_ARLO) // Acked, so send next byte
{ s->DR = sendBuffer[txCount++];
// Arbitration lost, restart bytesToSend--;
s->SR1 &= ~(I2C_SR1_ARLO); // Clear ARLO } else if (bytesToReceive) {
I2C_sendStart(); // Reinitiate request // Last sent byte acked and no more to send. Send repeated start, address and read bit.
transactionState = TS_START; // s->I2CM.ADDR.bit.ADDR = (deviceAddress << 1) | 1;
} } else {
else if (temp_sr1 & I2C_SR1_BERR) // Check both TxE/BTF == 1 before generating stop
{ while (!(s->SR1 && I2C_SR1_TXE)); // Check TxE
// Bus error while (!(s->SR1 && I2C_SR1_BTF)); // Check BTF
s->SR1 &= ~(I2C_SR1_BERR); // Clear BERR // No more data to send/receive. Initiate a STOP condition and finish
I2C_sendStop(); // Clear the bus I2C_sendStop();
transactionState = TS_IDLE;
completionStatus = I2C_STATUS_BUS_ERROR;
state = I2C_STATE_COMPLETED; state = I2C_STATE_COMPLETED;
} }
} } else if (s->SR1 && I2C_SR1_RXNE) {
else { // Master read completed without errors
// No error flags, so process event according to current state. if (bytesToReceive == 1) {
switch (transactionState) { // s->I2CM.CTRLB.bit.ACKACT = 1; // NAK final byte
case TS_START: I2C_sendStop(); // send stop
if (temp_sr1 & I2C_SR1_SB) { receiveBuffer[rxCount++] = s->DR; // Store received byte
// Event EV5 bytesToReceive = 0;
// Start bit has been sent successfully and we have the bus. state = I2C_STATE_COMPLETED;
// If anything to send, initiate write. Otherwise initiate read. } else if (bytesToReceive) {
if (operation == OPERATION_READ || ((operation == OPERATION_REQUEST) && !bytesToSend)) { // s->I2CM.CTRLB.bit.ACKACT = 0; // ACK all but final byte
// Send address with read flag (1) or'd in receiveBuffer[rxCount++] = s->DR; // Store received byte
s->DR = (deviceAddress << 1) | 1; // send the address bytesToReceive--;
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 {
// 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 */ #endif /* I2CMANAGER_STM32_H */

View File

@ -176,13 +176,6 @@ bool IODevice::exists(VPIN vpin) {
return findDevice(vpin) != NULL; 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. // check whether the pin supports notification. If so, then regular _read calls are not required.
bool IODevice::hasCallback(VPIN vpin) { bool IODevice::hasCallback(VPIN vpin) {
IODevice *dev = findDevice(vpin); IODevice *dev = findDevice(vpin);

View File

@ -27,6 +27,17 @@
// Define symbol DIAG_LOOPTIMES to enable CS loop execution time to be reported // Define symbol DIAG_LOOPTIMES to enable CS loop execution time to be reported
//#define DIAG_LOOPTIMES //#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 // 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 // animation has completed. This switches off the servo motor, preventing
// the continuous buzz sometimes found on servos, and reducing the // the continuous buzz sometimes found on servos, and reducing the
@ -154,9 +165,6 @@ public:
// exists checks whether there is a device owning the specified vpin // exists checks whether there is a device owning the specified vpin
static bool exists(VPIN 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 // 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. // 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 // Without the shared interrupt, input states are scanned periodically to detect changes on
@ -380,7 +388,6 @@ private:
uint8_t *_pinInUse; uint8_t *_pinInUse;
}; };
#ifndef IO_NO_HAL
///////////////////////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////////////////////
/* /*
* IODevice subclass for EX-Turntable. * IODevice subclass for EX-Turntable.
@ -409,14 +416,10 @@ private:
void _begin() override; void _begin() override;
void _loop(unsigned long currentMicros) override; void _loop(unsigned long currentMicros) override;
int _read(VPIN vpin) 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 _writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_t duration) override;
void _display() override; void _display() override;
uint8_t _stepperStatus; uint8_t _stepperStatus;
uint8_t _previousStatus;
uint8_t _currentActivity;
}; };
#endif
///////////////////////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////////////////////

View File

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

View File

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

View File

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

View File

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

View File

@ -26,8 +26,7 @@
#include "MotorDriver.h" #include "MotorDriver.h"
#include "DCCTimer.h" #include "DCCTimer.h"
#include "DIAG.h" #include "DIAG.h"
#include "CommandDistributor.h" #include"CommandDistributor.h"
#include "DCCEXParser.h"
// Virtualised Motor shield multi-track hardware Interface // Virtualised Motor shield multi-track hardware Interface
#define FOR_EACH_TRACK(t) for (byte t=0;t<=lastTrack;t++) #define FOR_EACH_TRACK(t) for (byte t=0;t<=lastTrack;t++)
@ -155,16 +154,10 @@ void TrackManager::setDCCSignal( bool on) {
HAVE_PORTA(shadowPORTA=PORTA); HAVE_PORTA(shadowPORTA=PORTA);
HAVE_PORTB(shadowPORTB=PORTB); HAVE_PORTB(shadowPORTB=PORTB);
HAVE_PORTC(shadowPORTC=PORTC); HAVE_PORTC(shadowPORTC=PORTC);
HAVE_PORTD(shadowPORTD=PORTD);
HAVE_PORTE(shadowPORTE=PORTE);
HAVE_PORTF(shadowPORTF=PORTF);
APPLY_BY_MODE(TRACK_MODE_MAIN,setSignal(on)); APPLY_BY_MODE(TRACK_MODE_MAIN,setSignal(on));
HAVE_PORTA(PORTA=shadowPORTA); HAVE_PORTA(PORTA=shadowPORTA);
HAVE_PORTB(PORTB=shadowPORTB); HAVE_PORTB(PORTB=shadowPORTB);
HAVE_PORTC(PORTC=shadowPORTC); HAVE_PORTC(PORTC=shadowPORTC);
HAVE_PORTD(PORTD=shadowPORTD);
HAVE_PORTE(PORTE=shadowPORTE);
HAVE_PORTF(PORTF=shadowPORTF);
} }
void TrackManager::setCutout( bool on) { void TrackManager::setCutout( bool on) {
@ -179,16 +172,10 @@ void TrackManager::setPROGSignal( bool on) {
HAVE_PORTA(shadowPORTA=PORTA); HAVE_PORTA(shadowPORTA=PORTA);
HAVE_PORTB(shadowPORTB=PORTB); HAVE_PORTB(shadowPORTB=PORTB);
HAVE_PORTC(shadowPORTC=PORTC); HAVE_PORTC(shadowPORTC=PORTC);
HAVE_PORTD(shadowPORTD=PORTD);
HAVE_PORTE(shadowPORTE=PORTE);
HAVE_PORTF(shadowPORTF=PORTF);
APPLY_BY_MODE(TRACK_MODE_PROG,setSignal(on)); APPLY_BY_MODE(TRACK_MODE_PROG,setSignal(on));
HAVE_PORTA(PORTA=shadowPORTA); HAVE_PORTA(PORTA=shadowPORTA);
HAVE_PORTB(PORTB=shadowPORTB); HAVE_PORTB(PORTB=shadowPORTB);
HAVE_PORTC(PORTC=shadowPORTC); HAVE_PORTC(PORTC=shadowPORTC);
HAVE_PORTD(PORTD=shadowPORTD);
HAVE_PORTE(PORTE=shadowPORTE);
HAVE_PORTF(PORTF=shadowPORTF);
} }
// setDCSignal(), called from normal context // setDCSignal(), called from normal context
@ -332,7 +319,6 @@ bool TrackManager::parseJ(Print *stream, int16_t params, int16_t p[])
FOR_EACH_TRACK(t) FOR_EACH_TRACK(t)
streamTrackState(stream,t); streamTrackState(stream,t);
return true; return true;
} }
p[0]-=HASH_KEYWORD_A; // convert A... to 0.... p[0]-=HASH_KEYWORD_A; // convert A... to 0....
@ -367,36 +353,32 @@ void TrackManager::streamTrackState(Print* stream, byte t) {
// null stream means send to commandDistributor for broadcast // null stream means send to commandDistributor for broadcast
if (track[t]==NULL) return; if (track[t]==NULL) return;
auto format=F(""); auto format=F("");
bool pstate = TrackManager::isPowerOn(t);
switch(track[t]->getMode()) { switch(track[t]->getMode()) {
case TRACK_MODE_MAIN: case TRACK_MODE_MAIN:
if (pstate) {format=F("<= %c MAIN ON>\n");} else {format = F("<= %c MAIN OFF>\n");} format=F("<= %c MAIN>\n");
break; break;
#ifndef DISABLE_PROG #ifndef DISABLE_PROG
case TRACK_MODE_PROG: case TRACK_MODE_PROG:
if (pstate) {format=F("<= %c PROG ON>\n");} else {format=F("<= %c PROG OFF>\n");} format=F("<= %c PROG>\n");
break; break;
#endif #endif
case TRACK_MODE_NONE: case TRACK_MODE_NONE:
if (pstate) {format=F("<= %c NONE ON>\n");} else {format=F("<= %c NONE OFF>\n");} format=F("<= %c NONE>\n");
break; break;
case TRACK_MODE_EXT: case TRACK_MODE_EXT:
if (pstate) {format=F("<= %c EXT ON>\n");} else {format=F("<= %c EXT OFF>\n");} format=F("<= %c EXT>\n");
break; break;
case TRACK_MODE_DC: case TRACK_MODE_DC:
if (pstate) {format=F("<= %c DC %d ON>\n");} else {format=F("<= %c DC %d OFF>\n");} format=F("<= %c DC %d>\n");
break; break;
case TRACK_MODE_DCX: case TRACK_MODE_DCX:
if (pstate) {format=F("<= %c DCX %d ON>\n");} else {format=F("<= %c DCX %d OFF>\n");} format=F("<= %c DCX %d>\n");
break; break;
default: default:
break; // unknown, dont care break; // unknown, dont care
} }
if (stream) StringFormatter::send(stream,format,'A'+t,trackDCAddr[t]);
if (stream) StringFormatter::send(stream,format,'A'+t, trackDCAddr[t]); else CommandDistributor::broadcastTrackState(format,'A'+t,trackDCAddr[t]);
else CommandDistributor::broadcastTrackState(format,'A'+t, trackDCAddr[t]);
} }
byte TrackManager::nextCycleTrack=MAX_TRACKS; byte TrackManager::nextCycleTrack=MAX_TRACKS;
@ -430,70 +412,49 @@ std::vector<MotorDriver *>TrackManager::getMainDrivers() {
} }
#endif #endif
void TrackManager::setPower2(bool setProg,bool setJoin, POWERMODE mode) { void TrackManager::setPower2(bool setProg,POWERMODE mode) {
if (!setProg) mainPowerGuess=mode; if (!setProg) mainPowerGuess=mode;
FOR_EACH_TRACK(t) { FOR_EACH_TRACK(t) {
MotorDriver * driver=track[t];
TrackManager::setTrackPower(setProg, setJoin, mode, t); if (!driver) continue;
switch (track[t]->getMode()) {
} case TRACK_MODE_MAIN:
return; if (setProg) break;
} // toggle brake before turning power on - resets overcurrent error
// on the Pololu board if brake is wired to ^D2.
void TrackManager::setTrackPower(bool setProg, bool setJoin, POWERMODE mode, byte thistrack) { // XXX see if we can make this conditional
driver->setBrake(true);
//DIAG(F("SetTrackPower Processing Track %d"), thistrack); driver->setBrake(false); // DCC runs with brake off
MotorDriver * driver=track[thistrack]; driver->setPower(mode);
if (!driver) return; break;
case TRACK_MODE_DC:
switch (track[thistrack]->getMode()) { case TRACK_MODE_DCX:
case TRACK_MODE_MAIN: if (setProg) break;
if (setProg) break; driver->setBrake(true); // DC starts with brake on
// toggle brake before turning power on - resets overcurrent error applyDCSpeed(t); // speed match DCC throttles
// on the Pololu board if brake is wired to ^D2. driver->setPower(mode);
// XXX see if we can make this conditional break;
driver->setBrake(true); case TRACK_MODE_PROG:
driver->setBrake(false); // DCC runs with brake off if (!setProg) break;
driver->setPower(mode); driver->setBrake(true);
break; driver->setBrake(false);
case TRACK_MODE_DC: driver->setPower(mode);
case TRACK_MODE_DCX: break;
//DIAG(F("Processing track - %d setProg %d"), thistrack, setProg); case TRACK_MODE_EXT:
if (setProg || setJoin) break; driver->setBrake(true);
driver->setBrake(true); // DC starts with brake on driver->setBrake(false);
applyDCSpeed(thistrack); // speed match DCC throttles driver->setPower(mode);
driver->setPower(mode); break;
break; case TRACK_MODE_NONE:
case TRACK_MODE_PROG: break;
if (!setProg && !setJoin) break;
driver->setBrake(true);
driver->setBrake(false);
driver->setPower(mode);
break;
case TRACK_MODE_EXT:
driver->setBrake(true);
driver->setBrake(false);
driver->setPower(mode);
break;
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() { POWERMODE TrackManager::getProgPower() {
FOR_EACH_TRACK(t) FOR_EACH_TRACK(t)
if (track[t]->getMode()==TRACK_MODE_PROG) if (track[t]->getMode()==TRACK_MODE_PROG)
return track[t]->getPower(); return track[t]->getPower();
return POWERMODE::OFF; return POWERMODE::OFF;
} }
@ -565,32 +526,3 @@ bool TrackManager::isPowerOn(byte t) {
return true; 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,10 +39,6 @@ const byte TRACK_NUMBER_5=5, TRACK_NUMBER_F=5;
const byte TRACK_NUMBER_6=6, TRACK_NUMBER_G=6; const byte TRACK_NUMBER_6=6, TRACK_NUMBER_G=6;
const byte TRACK_NUMBER_7=7, TRACK_NUMBER_H=7; 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 { class TrackManager {
public: public:
static void Setup(const FSH * shieldName, static void Setup(const FSH * shieldName,
@ -64,14 +60,10 @@ class TrackManager {
#ifdef ARDUINO_ARCH_ESP32 #ifdef ARDUINO_ARCH_ESP32
static std::vector<MotorDriver *>getMainDrivers(); static std::vector<MotorDriver *>getMainDrivers();
#endif #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 setPower(POWERMODE mode) {setMainPower(mode); setProgPower(mode);}
static void setMainPower(POWERMODE mode) {setPower2(false,false,mode);} static void setMainPower(POWERMODE mode) {setPower2(false,mode);}
static void setProgPower(POWERMODE mode) {setPower2(true,false,mode);} static void setProgPower(POWERMODE mode) {setPower2(true,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 const int16_t MAX_TRACKS=8;
static bool setTrackMode(byte track, TRACK_MODE mode, int16_t DCaddr=0); static bool setTrackMode(byte track, TRACK_MODE mode, int16_t DCaddr=0);
@ -85,14 +77,9 @@ class TrackManager {
static void sampleCurrent(); static void sampleCurrent();
static void reportGauges(Print* stream); static void reportGauges(Print* stream);
static void reportCurrent(Print* stream); static void reportCurrent(Print* stream);
static void reportPowerChange(Print* stream, byte thistrack);
static void reportObsoleteCurrent(Print* stream); static void reportObsoleteCurrent(Print* stream);
static void streamTrackState(Print* stream, byte t); static void streamTrackState(Print* stream, byte t);
static bool isPowerOn(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 int16_t joinRelay;
static bool progTrackSyncMain; // true when prog track is a siding switched to main static bool progTrackSyncMain; // true when prog track is a siding switched to main

View File

@ -1,268 +0,0 @@
/*
* © 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

View File

@ -1,243 +0,0 @@
/*
* © 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 #define DISABLE_EEPROM
#endif #endif
// STM32 support for native I2C is awaiting development // STM32 support for native I2C is awaiting development
// #ifndef I2C_USE_WIRE #ifndef I2C_USE_WIRE
// #define I2C_USE_WIRE #define I2C_USE_WIRE
// #endif #endif
/* TODO when ready /* TODO when ready
#elif defined(ARDUINO_ARCH_RP2040) #elif defined(ARDUINO_ARCH_RP2040)
@ -213,19 +213,6 @@
// //
#define WIFI_SERIAL_LINK_SPEED 115200 #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 __has_include ( "myAutomation.h")
#if defined(HAS_ENOUGH_MEMORY) || defined(DISABLE_EEPROM) || defined(DISABLE_PROG) #if defined(HAS_ENOUGH_MEMORY) || defined(DISABLE_EEPROM) || defined(DISABLE_PROG)
#define EXRAIL_ACTIVE #define EXRAIL_ACTIVE

View File

@ -24,7 +24,6 @@
//#include "IO_TouchKeypad.h // Touch keypad with 16 keys //#include "IO_TouchKeypad.h // Touch keypad with 16 keys
//#include "IO_EXTurntable.h" // Turntable-EX turntable controller //#include "IO_EXTurntable.h" // Turntable-EX turntable controller
//#include "IO_EXFastClock.h" // FastClock driver //#include "IO_EXFastClock.h" // FastClock driver
//#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. // The function halSetup() is invoked from CS if it exists within the build.

View File

@ -30,7 +30,8 @@ include_dir = .
[env] [env]
build_flags = -Wall -Wextra build_flags = -Wall -Wextra
; monitor_filters = time monitor_filters = time
; lib_deps = adafruit/Adafruit ST7735 and ST7789 Library @ ^1.10.0
[env:samd21-dev-usb] [env:samd21-dev-usb]
platform = atmelsam platform = atmelsam
@ -59,7 +60,7 @@ framework = arduino
lib_deps = ${env.lib_deps} lib_deps = ${env.lib_deps}
monitor_speed = 115200 monitor_speed = 115200
monitor_echo = yes monitor_echo = yes
build_flags = -std=c++17 build_flags = -std=c++17 ; -DI2C_USE_WIRE -DDIAG_LOOPTIMES -DDIAG_IO
[env:mega2560-debug] [env:mega2560-debug]
platform = atmelavr platform = atmelavr
@ -71,7 +72,7 @@ lib_deps =
SPI SPI
monitor_speed = 115200 monitor_speed = 115200
monitor_echo = yes monitor_echo = yes
build_flags = -DDIAG_IO=2 -DDIAG_LOOPTIMES build_flags = -DDIAG_IO=2 -DDIAG_LOOPTIMES
[env:mega2560-no-HAL] [env:mega2560-no-HAL]
platform = atmelavr platform = atmelavr
@ -83,7 +84,7 @@ lib_deps =
SPI SPI
monitor_speed = 115200 monitor_speed = 115200
monitor_echo = yes monitor_echo = yes
build_flags = -DIO_NO_HAL build_flags = -DIO_NO_HAL
[env:mega2560-I2C-wire] [env:mega2560-I2C-wire]
platform = atmelavr platform = atmelavr
@ -107,7 +108,7 @@ lib_deps =
SPI SPI
monitor_speed = 115200 monitor_speed = 115200
monitor_echo = yes monitor_echo = yes
build_flags = build_flags = ; -DDIAG_LOOPTIMES
[env:mega328] [env:mega328]
platform = atmelavr platform = atmelavr
@ -189,75 +190,10 @@ platform = ststm32
board = nucleo_f446re board = nucleo_f446re
framework = arduino framework = arduino
lib_deps = ${env.lib_deps} lib_deps = ${env.lib_deps}
build_flags = -std=c++17 -Os -g2 -Wunused-variable build_flags = -std=c++17 -Os -g2 -Wunused-variable ; -DDIAG_LOOPTIMES ; -DDIAG_IO
monitor_speed = 115200 monitor_speed = 115200
monitor_echo = yes monitor_echo = yes
; 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] [env:Teensy3_2]
platform = teensy platform = teensy
board = teensy31 board = teensy31
@ -296,4 +232,5 @@ board = teensy41
framework = arduino framework = arduino
build_flags = -std=c++17 -Os -g2 build_flags = -std=c++17 -Os -g2
lib_deps = ${env.lib_deps} lib_deps = ${env.lib_deps}
lib_ignore = lib_ignore =

View File

@ -3,33 +3,7 @@
#include "StringFormatter.h" #include "StringFormatter.h"
#define VERSION "5.1.14" #define VERSION "5.1.5LCC"
// 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 // 5.0.0 - Make 4.2.69 the 5.0.0 release
// 4.2.69 - Bugfix: Make <!> work in DC mode // 4.2.69 - Bugfix: Make <!> work in DC mode
// 4.2.68 - Rename track mode OFF to NONE // 4.2.68 - Rename track mode OFF to NONE